diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index b75fb2f39dd98f7cab711dc395a59d112cd12060..01947c4c24406d87873a2ee0c624cedf31a3e860 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -22,6 +22,7 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) enumToString.insert(STEERING, "Steering"); enumToString.insert(HOLD, "Hold"); enumToString.insert(LOITER, "Loiter"); + enumToString.insert(FOLLOW, "Follow"); enumToString.insert(SIMPLE, "Simple"); enumToString.insert(AUTO, "Auto"); enumToString.insert(RTL, "RTL"); @@ -40,6 +41,7 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) supportedFlightModes << APMRoverMode(APMRoverMode::STEERING ,true); supportedFlightModes << APMRoverMode(APMRoverMode::HOLD ,true); supportedFlightModes << APMRoverMode(APMRoverMode::LOITER ,true); + supportedFlightModes << APMRoverMode(APMRoverMode::FOLLOW ,true); supportedFlightModes << APMRoverMode(APMRoverMode::SIMPLE ,true); supportedFlightModes << APMRoverMode(APMRoverMode::AUTO ,true); supportedFlightModes << APMRoverMode(APMRoverMode::RTL ,true); diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index 98d932ec329a78cec63d0bf647b0b78037f8aab8..64d61334f5963a3fc5a062968adeb168642e30d0 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -25,6 +25,7 @@ public: STEERING = 3, HOLD = 4, LOITER = 5, + FOLLOW = 6, SIMPLE = 7, AUTO = 10, RTL = 11,