Skip to content

Commit fc98488

Browse files
alireza787bclaude
andcommitted
examples: rename quality to quality_percent
Match proto field rename from MAVSDK-Proto PR #395 review feedback. Co-Authored-By: Claude Opus 4.6 <[email protected]>
1 parent f0f5daf commit fc98488

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

examples/vision_odometry.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
3535
Dependencies:
3636
This example requires extended Odometry fields (reset_counter,
37-
estimator_type, quality) from:
37+
estimator_type, quality_percent) from:
3838
- MAVSDK-Proto PR #395: add odometry fields to mocap proto
3939
- MAVSDK-Proto PR #396: fix MavFrame enum values
4040
- MAVSDK PR #2791: wire up new odometry fields in C++
@@ -100,7 +100,7 @@
100100
def validate_odometry_api():
101101
"""Verify that MAVSDK includes the extended Odometry fields.
102102
103-
This example uses reset_counter, estimator_type, and quality
103+
This example uses reset_counter, estimator_type, and quality_percent
104104
fields added by MAVSDK-Proto PR #395. If your MAVSDK version
105105
does not include these, you will see a clear error here.
106106
"""
@@ -111,7 +111,7 @@ def validate_odometry_api():
111111
if len(sig.parameters) <= 9:
112112
raise SystemExit(
113113
"\n[ERROR] This example requires extended Odometry fields"
114-
"\n(reset_counter, estimator_type, quality) that are not"
114+
"\n(reset_counter, estimator_type, quality_percent) that are not"
115115
"\npresent in your MAVSDK installation.\n"
116116
"\nThese fields are introduced by:"
117117
"\n - MAVSDK-Proto PR #395"
@@ -250,7 +250,7 @@ async def vio_feed_loop(drone):
250250
# Build and send ODOMETRY message with extended fields:
251251
# reset_counter: increment on VIO tracking reset
252252
# estimator_type: VIO (visual-inertial odometry)
253-
# quality: confidence percentage (see EKF2_EV_QMIN)
253+
# quality_percent: confidence 0-100, -1=unknown (EKF2_EV_QMIN)
254254
odom = Odometry(
255255
time_usec=0,
256256
frame_id=Odometry.MavFrame.MOCAP_NED,
@@ -262,7 +262,7 @@ async def vio_feed_loop(drone):
262262
velocity_covariance=nan_cov,
263263
reset_counter=reset_counter,
264264
estimator_type=Odometry.MavEstimatorType.VIO,
265-
quality=QUALITY_PERCENT,
265+
quality_percent=QUALITY_PERCENT,
266266
)
267267
await drone.mocap.set_odometry(odom)
268268
frame_count += 1

0 commit comments

Comments
 (0)