mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
Mavlink Receiver: Don't ack DO_SET_MODE commands (#27343)
01abe35563 introduced a handler for the
`MAV_CMD_DO_SET_MODE` enum, which directly forwards a vehicle command
into uORB. It did not disable immediate acknowledgement of this command directly in `mavlink_receiver`. This means that the command is always ack'd once with ACCEPTED prior to the ack issued from Commander
The fix is to set `send_ack=false` immediately after dispatching the
command message to uORB in mavlink receiver
This commit is contained in:
@@ -611,6 +611,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
|
||||
|
||||
} else if (cmd_mavlink.command == MAV_CMD_DO_SET_MODE) {
|
||||
_cmd_pub.publish(vehicle_command);
|
||||
send_ack = false; //Acknowledgement handled by Commander
|
||||
|
||||
} else if (cmd_mavlink.command == MAV_CMD_DO_AUTOTUNE_ENABLE) {
|
||||
|
||||
|
||||
Reference in New Issue
Block a user