mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
GCS_MAVLink: ensure payload space before sending message ack
Also add comment about how we shouldn't be sending this message at all.
This commit is contained in:
parent
bb542ca39a
commit
67bf00c1c3
@ -1947,8 +1947,14 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg)
|
||||
|
||||
const MAV_RESULT result = _set_mode_common(_base_mode, _custom_mode);
|
||||
|
||||
// send ACK or NAK
|
||||
mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result);
|
||||
// send ACK or NAK. Note that this is extraodinarily improper -
|
||||
// we are sending a command-ack for a message which is not a
|
||||
// command. The command we are acking (ID=11) doesn't actually
|
||||
// exist, but if it did we'd probably be acking something
|
||||
// completely unrelated to setting modes.
|
||||
if (HAVE_PAYLOAD_SPACE(chan, MAVLINK_MSG_ID_COMMAND_ACK)) {
|
||||
mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user