Browse Source

GCS_MAVLink: correct frame on rally mission items

mission-4.1.18
Peter Barker 6 years ago committed by Peter Barker
parent
commit
71533c7c5c
  1. 2
      libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp

2
libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp

@ -83,7 +83,7 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::get_item(const GCS_MAVLINK &_link, @@ -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…
Cancel
Save