Last active
December 8, 2023 20:19
-
-
Save dbaldwin/2b10af0f50fa3b5f8facf0a620b8dc3d to your computer and use it in GitHub Desktop.
MAVSDK Box Mission Test
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
# On Raspberry Pi to Windows PC running MAVSDK server | |
sudo mavproxy.py --master=/dev/serial0 --baudrate 57600 --out 192.168.86.29:14550 | |
# On RPi4 with telemetry cable | |
mavproxy.py --master=/dev/ttyAMA0 --baudrate 57600 --out 192.168.11.116:14550 | |
# On Windows PC | |
.\mavsdk_server_win32.exe udp://:14550 | |
# Modified from MAVSDK script | |
# https://github.com/mavlink/MAVSDK-Python/blob/main/examples/offboard_position_ned.py | |
#!/usr/bin/env python3 | |
""" | |
Caveat when attempting to run the examples in non-gps environments: | |
`drone.offboard.stop()` will return a `COMMAND_DENIED` result because it | |
requires a mode switch to HOLD, something that is currently not supported in a | |
non-gps environment. | |
""" | |
import asyncio | |
from mavsdk import System | |
from mavsdk.offboard import (OffboardError, PositionNedYaw) | |
async def run(): | |
""" Does Offboard control using position NED coordinates. """ | |
drone = System(mavsdk_server_address="127.0.0.1") | |
await drone.connect(system_address="udp://:14550") | |
print("-- Arming") | |
await drone.action.arm() | |
print("-- Setting initial setpoint") | |
await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, 0.0, 0.0)) | |
print("-- Starting offboard") | |
try: | |
await drone.offboard.start() | |
except OffboardError as error: | |
print(f"Starting offboard mode failed with error code: {error._result.result}") | |
print("-- Disarming") | |
await drone.action.disarm() | |
return | |
print("takeoff") | |
await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, -1.5, 0.0)) # takeoff | |
await asyncio.sleep(10) | |
print("forward") | |
await drone.offboard.set_position_ned(PositionNedYaw(1.0, 0.0, -1.5, 0.0)) # fly forward | |
await asyncio.sleep(10) | |
print("right") | |
await drone.offboard.set_position_ned(PositionNedYaw(1.0, 1.0, -1.5, 0.0)) # fly front right corner | |
await asyncio.sleep(10) | |
print("back") | |
await drone.offboard.set_position_ned(PositionNedYaw(0.0, 1.0, -1.5, 0.0)) # fly rear right corner | |
await asyncio.sleep(10) | |
print("left") | |
await drone.offboard.set_position_ned(PositionNedYaw(0.0, 0.0, -1.5, 0.0)) # fly left right corner | |
await asyncio.sleep(10) | |
print("landing") | |
await drone.action.land() | |
await asyncio.sleep(10) | |
print("-- Stopping offboard") | |
try: | |
await drone.offboard.stop() | |
except OffboardError as error: | |
print(f"Stopping offboard mode failed with error code: {error._result.result}") | |
if __name__ == "__main__": | |
loop = asyncio.get_event_loop() | |
loop.run_until_complete(run()) | |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment