mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
GCS_MAVLink: correct frame on rally mission items
This commit is contained in:
parent
a3b5ed442c
commit
71533c7c5c
@ -83,7 +83,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::get_item(const GCS_MAVLINK &_link,
|
||||
return MAV_MISSION_INVALID_SEQUENCE;
|
||||
}
|
||||
|
||||
ret_packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT_INT;
|
||||
ret_packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
ret_packet.command = MAV_CMD_NAV_RALLY_POINT;
|
||||
ret_packet.x = rallypoint.lat;
|
||||
ret_packet.y = rallypoint.lng;
|
||||
|
Loading…
Reference in New Issue
Block a user