mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
GCS_MAVLink: correct payload space check for mission requests
This commit is contained in:
parent
8e19e805c6
commit
e4120c848c
@ -851,7 +851,7 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio
|
|||||||
} else {
|
} else {
|
||||||
waypoint_timelast_request = AP_HAL::millis();
|
waypoint_timelast_request = AP_HAL::millis();
|
||||||
// if we have enough space, then send the next WP request immediately
|
// if we have enough space, then send the next WP request immediately
|
||||||
if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) {
|
if (HAVE_PAYLOAD_SPACE(chan, MISSION_REQUEST)) {
|
||||||
queued_mission_request_send();
|
queued_mission_request_send();
|
||||||
} else {
|
} else {
|
||||||
send_message(MSG_NEXT_MISSION_REQUEST);
|
send_message(MSG_NEXT_MISSION_REQUEST);
|
||||||
|
Loading…
Reference in New Issue
Block a user