mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: always allow HOME to be read by MISSION_REQUEST
Fixes #5980
This commit is contained in:
parent
4bfc3d46a2
commit
564ff3a468
|
@ -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…
Reference in New Issue