Skip to content

Commit f0f5daf

Browse files
alireza787bclaude
andcommitted
examples: remove auto-takeoff, make VIO feed a background tool
The vision odometry example now does NOT arm, takeoff, or control the drone. It only feeds VIO data. The user flies the drone however they like (QGroundControl, RC, mission, another script) while this runs alongside. Press Ctrl+C to stop. Co-Authored-By: Claude Opus 4.6 <noreply@anthropic.com>
1 parent 347a686 commit f0f5daf

File tree

1 file changed

+41
-67
lines changed

1 file changed

+41
-67
lines changed

examples/vision_odometry.py

Lines changed: 41 additions & 67 deletions
Original file line numberDiff line numberDiff line change
@@ -3,18 +3,24 @@
33
"""
44
Vision Odometry Ground Truth Feedback -- MAVSDK Example
55
6-
Demonstrates VIO (Visual-Inertial Odometry) integration with PX4 using
7-
the MAVSDK Mocap plugin. In simulation, it reads the drone's actual
8-
position as "ground truth" and feeds it back to PX4 as external vision
9-
data, with configurable noise and delay to simulate a real VIO sensor.
6+
Feeds simulated VIO (Visual-Inertial Odometry) data to PX4 using the
7+
MAVSDK Mocap plugin. Reads the simulator's ground truth position, adds
8+
configurable noise and delay, and sends it back as external vision
9+
odometry. This is for testing and education -- the simulator looks
10+
and behaves completely normally while this script runs alongside it.
11+
12+
This script does NOT arm, takeoff, or control the drone in any way.
13+
You fly the drone however you like (QGroundControl, RC, mission, or
14+
another MAVSDK script) while this script feeds VIO data in the
15+
background. Press Ctrl+C to stop.
1016
1117
How it works:
1218
1. Connects to PX4 and configures EKF2 for vision fusion
13-
2. Arms and takes off (using GPS in simulation)
14-
3. Reads position from the simulator as ground truth
15-
4. Adds configurable Gaussian noise and delay
16-
5. Sends the result to PX4 as ODOMETRY at 30 Hz via Mocap plugin
17-
6. Displays real-time EKF2 position so you can see fusion working
19+
2. Reads position from the simulator as ground truth
20+
3. Adds configurable Gaussian noise and delay
21+
4. Sends the result to PX4 as ODOMETRY at 30 Hz via Mocap plugin
22+
5. Displays real-time EKF2 position and fusion health status
23+
6. Runs until you press Ctrl+C
1824
1925
Adjust the parameters below to experiment:
2026
- Increase NOISE_POS_STDDEV_M to see EKF2 handle noisy data
@@ -35,7 +41,11 @@
3541
Install a MAVSDK build that includes these changes.
3642
3743
Usage:
38-
python3 vision_odometry.py
44+
1. Start PX4 simulator
45+
2. Run: python3 vision_odometry.py
46+
3. Fly the drone normally (QGroundControl, RC, mission, etc.)
47+
4. Watch the VIO feed and EKF2 fusion status in the terminal
48+
5. Press Ctrl+C to stop
3949
"""
4050

4151
import asyncio
@@ -66,9 +76,7 @@
6676
DELAY_MS = 0 # Sensor delay (ms). Real: 10-50. 0 = off.
6777
QUALITY_PERCENT = 75 # Confidence 0-100. See EKF2_EV_QMIN.
6878

69-
# -- Flight --
70-
FLIGHT_ALT_M = 5.0 # Takeoff altitude (m)
71-
HOVER_TIME_S = 30 # How long to feed VIO while hovering (s)
79+
# -- Display --
7280
DISPLAY_INTERVAL_S = 2.0 # Status print interval (s)
7381

7482
# -- EKF2 Vision Fusion --
@@ -96,7 +104,6 @@ def validate_odometry_api():
96104
fields added by MAVSDK-Proto PR #395. If your MAVSDK version
97105
does not include these, you will see a clear error here.
98106
"""
99-
# Check constructor accepts the three new fields
100107
try:
101108
sig = inspect.signature(Odometry.__init__)
102109
# Original API: self + 8 fields = 9 params
@@ -115,7 +122,6 @@ def validate_odometry_api():
115122
except (ValueError, TypeError) as exc:
116123
raise SystemExit(f"[ERROR] Cannot inspect Odometry API: {exc}") from exc
117124

118-
# Check MavEstimatorType enum exists
119125
if not hasattr(Odometry, "MavEstimatorType"):
120126
raise SystemExit(
121127
"[ERROR] Odometry.MavEstimatorType not found.\n"
@@ -141,49 +147,20 @@ async def run():
141147
break
142148

143149
await configure_ekf2(drone)
144-
145-
print("\nWaiting for position estimate...")
146-
async for health in drone.telemetry.health():
147-
if health.is_global_position_ok and health.is_home_position_ok:
148-
print("[OK] Position estimate ready")
149-
break
150-
151-
print("\n-- Arming")
152-
await drone.action.arm()
153-
154-
print(f"-- Taking off to {FLIGHT_ALT_M:.0f} m")
155-
await drone.action.set_takeoff_altitude(FLIGHT_ALT_M)
156-
await drone.action.takeoff()
157-
158-
print("-- Waiting for takeoff...")
159-
await asyncio.sleep(10)
160-
print("[OK] Hovering -- starting VIO feed\n")
161-
162150
print_settings_summary()
163151

164-
# Run VIO feed, status monitor, and health watch concurrently
165-
stop_event = asyncio.Event()
166-
vio_task = asyncio.ensure_future(vio_feed_loop(drone, stop_event))
167-
monitor_task = asyncio.ensure_future(monitor_status(drone, stop_event))
168-
health_task = asyncio.ensure_future(watch_fusion_health(drone, stop_event))
169-
170-
await asyncio.sleep(HOVER_TIME_S)
171-
stop_event.set()
172-
173-
await asyncio.gather(
174-
vio_task,
175-
monitor_task,
176-
health_task,
177-
return_exceptions=True,
178-
)
152+
print("VIO feed is running. Fly the drone normally")
153+
print("(QGroundControl, RC, mission, etc.). Press Ctrl+C to stop.\n")
179154

180-
print("\n-- Landing")
181-
await drone.action.land()
155+
# Run VIO feed, status monitor, and health watch concurrently
156+
vio_task = asyncio.ensure_future(vio_feed_loop(drone))
157+
monitor_task = asyncio.ensure_future(monitor_status(drone))
158+
health_task = asyncio.ensure_future(watch_fusion_health(drone))
182159

183-
async for in_air in drone.telemetry.in_air():
184-
if not in_air:
185-
print("[OK] Landed")
186-
break
160+
try:
161+
await asyncio.gather(vio_task, monitor_task, health_task)
162+
except asyncio.CancelledError:
163+
pass
187164

188165
print_footer()
189166

@@ -199,6 +176,7 @@ async def configure_ekf2(drone):
199176
for name, value, desc in params:
200177
await drone.param.set_param_int(name, value)
201178
print(f" {name:20s} = {value:2d} ({desc})")
179+
print()
202180

203181

204182
def print_settings_summary():
@@ -220,7 +198,7 @@ def print_settings_summary():
220198
# ===================================================================
221199

222200

223-
async def vio_feed_loop(drone, stop_event):
201+
async def vio_feed_loop(drone):
224202
"""Read ground truth, add noise/delay, send as vision odometry.
225203
226204
In simulation, position_velocity_ned() returns the EKF2 estimate,
@@ -245,9 +223,6 @@ async def vio_feed_loop(drone, stop_event):
245223
delay_buf = None
246224

247225
async for pos_vel in drone.telemetry.position_velocity_ned():
248-
if stop_event.is_set():
249-
break
250-
251226
n = pos_vel.position.north_m
252227
e = pos_vel.position.east_m
253228
d = pos_vel.position.down_m
@@ -302,7 +277,7 @@ async def vio_feed_loop(drone, stop_event):
302277
# ===================================================================
303278

304279

305-
async def monitor_status(drone, stop_event):
280+
async def monitor_status(drone):
306281
"""Print EKF2 position at regular intervals."""
307282
print(
308283
f"{'Time':>6s} {'North':>8s} {'East':>8s} {'Down':>8s} {'Vn':>6s} {'Ve':>6s} {'Vd':>6s}"
@@ -313,9 +288,6 @@ async def monitor_status(drone, stop_event):
313288
last_print = 0.0
314289

315290
async for pv in drone.telemetry.position_velocity_ned():
316-
if stop_event.is_set():
317-
break
318-
319291
elapsed = time.monotonic() - start
320292
if elapsed - last_print < DISPLAY_INTERVAL_S:
321293
await asyncio.sleep(0.2)
@@ -334,13 +306,11 @@ async def monitor_status(drone, stop_event):
334306
)
335307

336308

337-
async def watch_fusion_health(drone, stop_event):
309+
async def watch_fusion_health(drone):
338310
"""Report EKF2 fusion health changes."""
339311
was_ok = False
340312

341313
async for health in drone.telemetry.health():
342-
if stop_event.is_set():
343-
break
344314
is_ok = health.is_local_position_ok
345315
if is_ok and not was_ok:
346316
print("[HEALTH] Local position OK -- vision fusion active")
@@ -353,7 +323,8 @@ def print_footer():
353323
"""Print final guidance for the user."""
354324
print()
355325
print("=" * 60)
356-
print("Done! Adjust parameters at the top of this file:")
326+
print("VIO feed stopped. Adjust parameters at the top of")
327+
print("this file to experiment:")
357328
print(" NOISE_POS_STDDEV_M -- increase to stress EKF2")
358329
print(" DELAY_MS -- simulate sensor latency")
359330
print(" QUALITY_PERCENT -- lower with EKF2_EV_QMIN > 0")
@@ -362,4 +333,7 @@ def print_footer():
362333

363334

364335
if __name__ == "__main__":
365-
asyncio.run(run())
336+
try:
337+
asyncio.run(run())
338+
except KeyboardInterrupt:
339+
print("\n[OK] Stopped by user")

0 commit comments

Comments
 (0)