mirror of https://github.com/ArduPilot/ardupilot
ArduSub: emit MAV_RESULT_DENIED if start/stop item passed to MAV_CMD_MISSION_START
This commit is contained in:
parent
d8252d81f8
commit
f53fcffbf6
|
@ -542,6 +542,10 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_
|
||||||
return handle_command_int_do_reposition(packet);
|
return handle_command_int_do_reposition(packet);
|
||||||
|
|
||||||
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;
|
||||||
|
}
|
||||||
return handle_MAV_CMD_MISSION_START(packet);
|
return handle_MAV_CMD_MISSION_START(packet);
|
||||||
|
|
||||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||||
|
|
Loading…
Reference in New Issue