mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: update ModeReasons to not use UNKNOWN reason
This commit is contained in:
parent
88d28460f5
commit
c7c9461fc0
@ -463,7 +463,7 @@ void Plane::update_navigation()
|
||||
are within the maximum of the stopping distance and the
|
||||
RTL_RADIUS
|
||||
*/
|
||||
set_mode(mode_qrtl, ModeReason::UNKNOWN);
|
||||
set_mode(mode_qrtl, ModeReason::RTL_COMPLETE_SWITCHING_TO_VTOL_LAND_RTL);
|
||||
break;
|
||||
} else if (g.rtl_autoland == 1 &&
|
||||
!auto_state.checked_for_autoland &&
|
||||
@ -473,7 +473,7 @@ void Plane::update_navigation()
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
mission.set_force_resume(true);
|
||||
set_mode(mode_auto, ModeReason::UNKNOWN);
|
||||
set_mode(mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND);
|
||||
}
|
||||
|
||||
// prevent running the expensive jump_to_landing_sequence
|
||||
@ -486,7 +486,7 @@ void Plane::update_navigation()
|
||||
if (mission.jump_to_landing_sequence()) {
|
||||
// switch from RTL -> AUTO
|
||||
mission.set_force_resume(true);
|
||||
set_mode(mode_auto, ModeReason::UNKNOWN);
|
||||
set_mode(mode_auto, ModeReason::RTL_COMPLETE_SWITCHING_TO_FIXEDWING_AUTOLAND);
|
||||
}
|
||||
|
||||
// prevent running the expensive jump_to_landing_sequence
|
||||
|
@ -72,7 +72,7 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
||||
set_mode(mode_rtl, ModeReason::UNKNOWN);
|
||||
set_mode(mode_rtl, ModeReason::MISSION_CMD);
|
||||
break;
|
||||
|
||||
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
|
||||
|
@ -142,7 +142,7 @@ void Plane::init_ardupilot()
|
||||
// choose the nav controller
|
||||
set_nav_controller();
|
||||
|
||||
set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::UNKNOWN);
|
||||
set_mode_by_number((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED);
|
||||
|
||||
// set the correct flight mode
|
||||
// ---------------------------
|
||||
@ -169,7 +169,7 @@ void Plane::init_ardupilot()
|
||||
//********************************************************************************
|
||||
void Plane::startup_ground(void)
|
||||
{
|
||||
set_mode(mode_initializing, ModeReason::UNKNOWN);
|
||||
set_mode(mode_initializing, ModeReason::INITIALISED);
|
||||
|
||||
#if (GROUND_START_DELAY > 0)
|
||||
gcs().send_text(MAV_SEVERITY_NOTICE,"Ground start with delay");
|
||||
|
Loading…
Reference in New Issue
Block a user