mirror of https://github.com/ArduPilot/ardupilot
Rover: emit MAV_RESULT_DENIED if start/stop item passed to MAV_CMD_MISSION_START
This commit is contained in:
parent
f53fcffbf6
commit
2ec045fdc0
|
@ -701,6 +701,10 @@ MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_in
|
|||
packet.param4);
|
||||
|
||||
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)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue