Skip to content

Commit

Permalink
GCS_MAVLink: Remove wrong usage of COMMAND_ACK message
Browse files Browse the repository at this point in the history
SET_MODE message does not exist inside the MAV_CMD enum
as described in the mavlink specification.
The system that is using SET_MODE to communicate with the
vehicle should rely on HEARTBEAT message to detect if
the mode was set correctly.

Signed-off-by: Patrick José Pereira <[email protected]>
  • Loading branch information
patrickelectric authored and tridge committed Feb 19, 2024
1 parent a404693 commit 3f2c82d
Showing 1 changed file with 1 addition and 13 deletions.
14 changes: 1 addition & 13 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2618,19 +2618,7 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg)
const MAV_MODE _base_mode = (MAV_MODE)packet.base_mode;
const uint32_t _custom_mode = packet.custom_mode;

const MAV_RESULT result = _set_mode_common(_base_mode, _custom_mode);

// 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, COMMAND_ACK)) {
mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result,
0, 0,
msg.sysid,
msg.compid);
}
_set_mode_common(_base_mode, _custom_mode);
}

/*
Expand Down

0 comments on commit 3f2c82d

Please sign in to comment.