You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Here's the relavant part of the MAVSDK code that I'm using to create the mission:
frommavsdkimportSystemdrone=System()
awaitdrone.connect(system_address="udp://:14540")
print("Waiting for drone to connect...")
asyncforstateindrone.core.connection_state():
ifstate.is_connected:
print(f"-- Connected to drone!")
breakmission_items= []
mission_items.append(mission_raw.MissionItem(
0, # start seq at 01, # MAV_FRAME_LOCAL_NED enum value16, # MAV_CMD_NAV_WAYPOINT enum value1,
1,
0, 10, 0, float('nan'),
50, 50, -30.0, # N, E, D0
))
print("-- Uploading mission")
awaitdrone.mission_raw.upload_mission(mission_items)
print("-- Done")
However when I try to upload the mission, I get an error indicating that I have
invalid mission items.
mavsdk.mission_raw.MissionRawError: UNSUPPORTED: 'Unsupported'; origin: upload_mission(); params: ([<mavsdk.mission_raw.MissionItem object at 0x7b3ae853c5e0>],)
That happens because the mission item parser doesn't treat MAV_FRAME_LOCAL_NED as a supported frame.
Currently it's only possible to add waypoints to the mission using global coordinates, so it would be great to have the support for local coordinates during mission planning.
Solution
Add MAV_FRAME_LOCAL_NED as a supported frame for the mission items. The parser that doesn't recognize this frame as a valid one, is located in modules/mavlink/mavlink_mission.cpp named parse_mavlink_mission_item().
Problem description and how to reproduce
I am trying to plan a mission that uses local NED coordinates as waypoints.
I am creating mission items with MAV_FRAME_LOCAL_NED as MAV_FRAME for the MISSION_ITEM_INT, as defined by the MAVLink protocol:
https://mavlink.io/kr/messages/common.html#MISSION_ITEM_INT
https://mavlink.io/kr/messages/common.html#MAV_FRAME
Relevant code
Here's the relavant part of the MAVSDK code that I'm using to create the mission:
However when I try to upload the mission, I get an error indicating that I have
invalid mission items.
That happens because the mission item parser doesn't treat MAV_FRAME_LOCAL_NED as a supported frame.
Currently it's only possible to add waypoints to the mission using global coordinates, so it would be great to have the support for local coordinates during mission planning.
Solution
Add MAV_FRAME_LOCAL_NED as a supported frame for the mission items. The parser that doesn't recognize this frame as a valid one, is located in modules/mavlink/mavlink_mission.cpp named parse_mavlink_mission_item().
Possible alternatives
Add some other way of planning missions using local coordinates. Like adding MAV_FRAME_LOCAL_ENU or MAV_FRAME_LOCAL_OFFSET_NED as a supported frame.
The text was updated successfully, but these errors were encountered: