diff --git a/artoo/src/flightmanager.cpp b/artoo/src/flightmanager.cpp index 2b74cb6..88a7f27 100644 --- a/artoo/src/flightmanager.cpp +++ b/artoo/src/flightmanager.cpp @@ -65,6 +65,9 @@ const char *FlightManager::flightModeStr(FlightMode m) case AVOID_ADSB: return "ADS-B AVOID"; case GUIDED_NOGPS: return "Guided No GPS"; case SMART_RTL: return "Smart RTL"; + case FLOWHOLD: return "Flow Hold"; + case FOLLOW: return "Follow"; + case ZIGZAG: return "Zig Zag"; default: return "Unknown"; } } diff --git a/artoo/src/flightmanager.h b/artoo/src/flightmanager.h index e633f21..a56b2ec 100644 --- a/artoo/src/flightmanager.h +++ b/artoo/src/flightmanager.h @@ -36,6 +36,9 @@ public: AVOID_ADSB = 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft GUIDED_NOGPS = 20, // guided mode but only accepts attitude and altitude SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps + FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder + FOLLOW = 23, // Follow attempts to follow another vehicle or ground station + ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B }; /* @@ -104,7 +107,8 @@ public: } static const char *flightModeStr(FlightMode m); static bool flightModeIsAutonomous(FlightMode m) { - return (m == AUTO || m == GUIDED || m == LOITER || m == RTL || m == CIRCLE || m == DRIFT || m == POSHOLD || m == BRAKE || m == THROW || m == AVOID_ADSB || m == GUIDED_NOGPS || m == SMART_RTL ); + return (m == AUTO || m == GUIDED || m == LOITER || m == RTL || m == CIRCLE || m == DRIFT || m == POSHOLD || m == BRAKE || m == THROW || m == AVOID_ADSB || m == GUIDED_NOGPS || m == SMART_RTL || m == FLOWHOLD + || m == FOLLOW || m == ZIGZAG); } ALWAYS_INLINE bool currentFlightModeManual() const {