Rover: emit MAV_RESULT_DENIED if start/stop item passed to MAV_CMD_MISSION_START

This commit is contained in:
Peter Barker 2024-08-16 22:45:51 +10:00 committed by Andrew Tridgell
parent f53fcffbf6
commit 2ec045fdc0
1 changed files with 4 additions and 0 deletions

View File

@ -701,6 +701,10 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
packet.param4); packet.param4);
case MAV_CMD_MISSION_START: case MAV_CMD_MISSION_START:
if (!is_zero(packet.param1) || !is_zero(packet.param2)) {
// first-item/last item not supported
return MAV_RESULT_DENIED;
}
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) { if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED; return MAV_RESULT_ACCEPTED;
} }