diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 53b82dcd56..fd1a45b83b 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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, diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 86371565c4..dada70a03a 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -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 diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 129f13ffec..2b4aa70318 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -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)); } /********************************************************************************/