Copter: Support DO_LAND_START as an adhoc MAVLink command

This commit is contained in:
Michael du Breuil 2020-07-16 11:36:48 -07:00 committed by Randy Mackay
parent 6c6e4eff67
commit 08f8a41ecb

View File

@ -684,6 +684,12 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
return MAV_RESULT_ACCEPTED;
}
case MAV_CMD_DO_LAND_START:
if (copter.mode_auto.mission.jump_to_landing_sequence() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_FAILED;
case MAV_CMD_NAV_LOITER_UNLIM:
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::GCS_COMMAND)) {
return MAV_RESULT_FAILED;