Browse Source

Copter: move RTLState to ModeRTL

c415-sdk
Randy Mackay 5 years ago
parent
commit
39a6b104dd
  1. 10
      ArduCopter/defines.h
  2. 9
      ArduCopter/mode.h
  3. 4
      ArduCopter/mode_auto.cpp

10
ArduCopter/defines.h

@ -106,16 +106,6 @@ enum GuidedMode { @@ -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,

9
ArduCopter/mode.h

@ -1019,6 +1019,15 @@ public: @@ -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

4
ArduCopter/mode_auto.cpp

@ -1755,8 +1755,8 @@ bool ModeAuto::verify_loiter_to_alt() @@ -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…
Cancel
Save