From 07632dc7ed1d7c0375c85c2d09c58691ba3901cf Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 26 Jan 2021 12:37:02 +0100 Subject: [PATCH] Copter: move AutoMode to Auto class --- ArduCopter/defines.h | 14 -------------- ArduCopter/mode.h | 15 +++++++++++++++ 2 files changed, 15 insertions(+), 14 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 8aae036304..a7f2ae1470 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -83,20 +83,6 @@ enum tuning_func { #define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL 2 // auto pilot will face next waypoint except when doing RTL at which time it will stay in it's last #define WP_YAW_BEHAVIOR_LOOK_AHEAD 3 // auto pilot will look ahead during missions and rtl (primarily meant for traditional helicopters) -// Auto modes -enum class AutoMode : uint8_t { - TAKEOFF, - WP, - LAND, - RTL, - CIRCLE_MOVE_TO_EDGE, - CIRCLE, - SPLINE, - NAVGUIDED, - LOITER, - LOITER_TO_ALT, - NAV_PAYLOAD_PLACE, -}; // Airmode enum class AirMode { diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 29eeb295bd..a91947866f 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -360,6 +360,21 @@ public: bool is_autopilot() const override { return true; } bool in_guided_mode() const override { return mode() == AutoMode::NAVGUIDED; } + // Auto modes + enum class AutoMode : uint8_t { + TAKEOFF, + WP, + LAND, + RTL, + CIRCLE_MOVE_TO_EDGE, + CIRCLE, + SPLINE, + NAVGUIDED, + LOITER, + LOITER_TO_ALT, + NAV_PAYLOAD_PLACE, + }; + // Auto AutoMode mode() const { return _mode; }