forked from boom6314/Mavsdk_python
上傳檔案到「」
parent
c00dcb6cce
commit
6f0e261636
@ -0,0 +1,58 @@
|
||||
#!/usr/bin/env python3
|
||||
import asyncio
|
||||
from mavsdk import System
|
||||
from mavsdk.telemetry_server import (StatusText,StatusTextType,Battery,Position,VelocityNed, Heading,RawGps,GpsInfo,FixType)
|
||||
import random
|
||||
async def run():
|
||||
|
||||
drone = System(port=50053)
|
||||
print("456")
|
||||
|
||||
await drone.connect(system_address="udp://:14550")
|
||||
print("123")
|
||||
await drone.telemetry_server.publish_status_text(StatusText(StatusTextType.ALERT,"Check"))
|
||||
|
||||
|
||||
while True:
|
||||
|
||||
remaining_percent = random.uniform(0.0, 1.0)
|
||||
voltage_v = random.uniform(0.0, 20.0)
|
||||
|
||||
latitude_deg = random.uniform(0.0, 50.0)
|
||||
longitude_deg = random.uniform(0.0, 180.0)
|
||||
absolute_altitude_m = random.uniform(0.0, 50.0)
|
||||
relative_altitude_m = random.uniform(0.0, 50.0)
|
||||
heading_deg = random.uniform(0.0, 360.0)
|
||||
position = Position(latitude_deg, longitude_deg,absolute_altitude_m,relative_altitude_m)
|
||||
velocity_ned = VelocityNed(north_m_s=0.0, east_m_s=0.0, down_m_s=0.0)
|
||||
heading = Heading(heading_deg)
|
||||
|
||||
raw_gps = RawGps(
|
||||
timestamp_us=123456789, # 当前时间戳,以微秒为单位
|
||||
latitude_deg=47.3977418, # 纬度
|
||||
longitude_deg=8.5455934, # 经度
|
||||
absolute_altitude_m=500, # 绝对海拔高度(米)
|
||||
hdop=1.0, # 水平精度因子
|
||||
vdop=1.0, # 垂直精度因子
|
||||
velocity_m_s=random.uniform(0.0,50.0), # 速度(米/秒)
|
||||
cog_deg=90.0, # 航向(度)
|
||||
altitude_ellipsoid_m=510.0, # 大地水准面上的高度(米)
|
||||
horizontal_uncertainty_m=1.000000000000, # 水平准确性(米)
|
||||
vertical_uncertainty_m=1.00000000,
|
||||
velocity_uncertainty_m_s=0.0000000000000000 ,# 垂直准确性(米)
|
||||
heading_uncertainty_deg=1.0000000, # 速度准确性(米/秒)
|
||||
yaw_deg=180.5# 是否已定位的标志
|
||||
)
|
||||
gps_info = GpsInfo(
|
||||
num_satellites=10, # 卫星数量
|
||||
fix_type=FixType.RTK_FIXED # GPS 修复类型
|
||||
)
|
||||
await drone.telemetry_server.publish_battery(Battery(voltage_v,remaining_percent))
|
||||
await drone.telemetry_server.publish_position(position,velocity_ned,heading)
|
||||
await drone.telemetry_server.publish_raw_gps(raw_gps,gps_info)
|
||||
await asyncio.sleep(1)
|
||||
|
||||
#print("remaining_percent: ",remaining_percent)
|
||||
if __name__ == "__main__":
|
||||
loop = asyncio.get_event_loop()
|
||||
loop.run_until_complete(run())
|
||||
Loading…
Reference in New Issue