Copter: command long DO_LAND_START enters Auto RTL pseudo mode
This commit is contained in:
parent
6561669213
commit
885b12f179
@ -737,7 +737,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_
|
||||
|
||||
#if MODE_AUTO_ENABLED == ENABLED
|
||||
case MAV_CMD_DO_LAND_START:
|
||||
if (copter.mode_auto.mission.jump_to_landing_sequence() && copter.set_mode(Mode::Number::AUTO, ModeReason::GCS_COMMAND)) {
|
||||
if (copter.mode_auto.jump_to_landing_sequence_auto_RTL(ModeReason::GCS_COMMAND)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
return MAV_RESULT_FAILED;
|
||||
|
Loading…
Reference in New Issue
Block a user