mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: accept several mode-changing commands via command_int
... as well as via command_long
This commit is contained in:
parent
4a181ede62
commit
d54d9ae922
|
@ -795,6 +795,25 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
|
|||
return handle_MAV_CMD_DO_WINCH(packet);
|
||||
#endif
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_NAV_VTOL_LAND:
|
||||
case MAV_CMD_NAV_LAND:
|
||||
if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
||||
}
|
||||
|
@ -846,25 +865,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
|||
return MAV_RESULT_FAILED;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_NAV_LOITER_UNLIM:
|
||||
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
if (!copter.set_mode(Mode::Number::RTL, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
case MAV_CMD_NAV_VTOL_LAND:
|
||||
case MAV_CMD_NAV_LAND:
|
||||
if (!copter.set_mode(Mode::Number::LAND, ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
||||
default:
|
||||
return GCS_MAVLINK::handle_command_long_packet(packet, msg);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue