mirror of https://github.com/ArduPilot/ardupilot
Copter: move RTLState to ModeRTL
This commit is contained in:
parent
2e09acc2ae
commit
39a6b104dd
|
@ -106,16 +106,6 @@ enum GuidedMode {
|
|||
Guided_Angle,
|
||||
};
|
||||
|
||||
// RTL states
|
||||
enum RTLState {
|
||||
RTL_Starting,
|
||||
RTL_InitialClimb,
|
||||
RTL_ReturnHome,
|
||||
RTL_LoiterAtHome,
|
||||
RTL_FinalDescent,
|
||||
RTL_Land
|
||||
};
|
||||
|
||||
// Safe RTL states
|
||||
enum SmartRTLState {
|
||||
SmartRTL_WaitForPathCleanup,
|
||||
|
|
|
@ -1019,6 +1019,15 @@ public:
|
|||
// for reporting to GCS
|
||||
bool get_wp(Location &loc) override;
|
||||
|
||||
// RTL states
|
||||
enum RTLState {
|
||||
RTL_Starting,
|
||||
RTL_InitialClimb,
|
||||
RTL_ReturnHome,
|
||||
RTL_LoiterAtHome,
|
||||
RTL_FinalDescent,
|
||||
RTL_Land
|
||||
};
|
||||
RTLState state() { return _state; }
|
||||
|
||||
// this should probably not be exposed
|
||||
|
|
|
@ -1755,8 +1755,8 @@ bool ModeAuto::verify_loiter_to_alt()
|
|||
bool ModeAuto::verify_RTL()
|
||||
{
|
||||
return (copter.mode_rtl.state_complete() &&
|
||||
(copter.mode_rtl.state() == RTL_FinalDescent || copter.mode_rtl.state() == RTL_Land) &&
|
||||
(motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE));
|
||||
(copter.mode_rtl.state() == ModeRTL::RTL_FinalDescent || copter.mode_rtl.state() == ModeRTL::RTL_Land) &&
|
||||
(motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE));
|
||||
}
|
||||
|
||||
/********************************************************************************/
|
||||
|
|
Loading…
Reference in New Issue