Browse Source

GCS_MAVLink: always allow HOME to be read by MISSION_REQUEST

Fixes #5980
master
Peter Barker 8 years ago
parent
commit
564ff3a468
  1. 3
      libraries/GCS_MAVLink/GCS_Common.cpp

3
libraries/GCS_MAVLink/GCS_Common.cpp

@ -337,7 +337,8 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t @@ -337,7 +337,8 @@ void GCS_MAVLINK::handle_mission_request(AP_Mission &mission, mavlink_message_t
mavlink_mission_request_t packet;
mavlink_msg_mission_request_decode(msg, &packet);
if (packet.seq >= mission.num_commands()) {
if (packet.seq != 0 && // always allow HOME to be read
packet.seq >= mission.num_commands()) {
// try to educate the GCS on the actual size of the mission:
mavlink_msg_mission_count_send(chan,msg->sysid, msg->compid, mission.num_commands());
goto mission_item_send_failed;

Loading…
Cancel
Save