1 Star 0 Fork 0

mavlink/MAVSDK-Python

加入 Gitee
与超过 1400万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
克隆/下载
offboard_attitude.py 2.27 KB
一键复制 编辑 原始数据 按行查看 历史
Julian Oes 提交于 2023-01-14 04:23 +08:00 . examples: switch to newer asyncio API
#!/usr/bin/env python3
# Warning: Only try this in simulation!
# The direct attitude interface is a low level interface to be used
# with caution. On real vehicles the thrust values are likely not
# adjusted properly and you need to close the loop using altitude.
import asyncio
from mavsdk import System
from mavsdk.offboard import (Attitude, OffboardError)
async def run():
""" Does Offboard control using attitude commands. """
drone = System()
await drone.connect(system_address="udp://:14540")
print("Waiting for drone to connect...")
async for state in drone.core.connection_state():
if state.is_connected:
print(f"-- Connected to drone!")
break
print("Waiting for drone to have a global position estimate...")
async for health in drone.telemetry.health():
if health.is_global_position_ok and health.is_home_position_ok:
print("-- Global position estimate OK")
break
print("-- Arming")
await drone.action.arm()
print("-- Setting initial setpoint")
await drone.offboard.set_attitude(Attitude(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("-- Go up at 70% thrust")
await drone.offboard.set_attitude(Attitude(0.0, 0.0, 0.0, 0.7))
await asyncio.sleep(2)
print("-- Roll 30 at 60% thrust")
await drone.offboard.set_attitude(Attitude(30.0, 0.0, 0.0, 0.6))
await asyncio.sleep(2)
print("-- Roll -30 at 60% thrust")
await drone.offboard.set_attitude(Attitude(-30.0, 0.0, 0.0, 0.6))
await asyncio.sleep(2)
print("-- Hover at 60% thrust")
await drone.offboard.set_attitude(Attitude(0.0, 0.0, 0.0, 0.6))
await asyncio.sleep(2)
print("-- Stopping offboard")
try:
await drone.offboard.stop()
except OffboardError as error:
print(f"Stopping offboard mode failed with error code: \
{error._result.result}")
await drone.action.land()
if __name__ == "__main__":
# Run the asyncio loop
asyncio.run(run())
Loading...
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/mavlink/MAVSDK-Python.git
git@gitee.com:mavlink/MAVSDK-Python.git
mavlink
MAVSDK-Python
MAVSDK-Python
main

搜索帮助