diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 21cb154468a816d5a252a9db3636bf6a62ec0209..3af285e00b90a4e924184072459b985780fee982 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -43,7 +43,10 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : { GUIDED_NOGPS, "Guided No GPS"}, { SMART_RTL, "Smart RTL"}, { FLOWHOLD, "Flow Hold" }, +#if 0 + // Follow me not ready for Stable { FOLLOW, "Follow" }, +#endif { ZIGZAG, "ZigZag" }, }); } @@ -71,7 +74,10 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), APMCopterMode(APMCopterMode::SMART_RTL, true), APMCopterMode(APMCopterMode::FLOWHOLD, true), +#if 0 + // Follow me not ready for Stable APMCopterMode(APMCopterMode::FOLLOW, true), +#endif APMCopterMode(APMCopterMode::ZIGZAG, true), }); diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index bd87214a9a33f01cebe5758b8454d4b9bce8a74b..05c596994f8964498e2efd3c2f051cd7b679817e 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -43,7 +43,10 @@ public: GUIDED_NOGPS= 20, SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder +#if 0 + // Follow me not ready for Stable FOLLOW = 23, // follow attempts to follow another vehicle or ground station +#endif ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B }; diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index c5e9376eec8396b3cf62686a4a326a543b915626..0dbef83d0970fff7235478c87968cafb9c85679c 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) {STEERING, "Steering"}, {HOLD, "Hold"}, {LOITER, "Loiter"}, +#if 0 + // Follow me not ready for Stable {FOLLOW, "Follow"}, +#endif {SIMPLE, "Simple"}, {AUTO, "Auto"}, {RTL, "RTL"}, @@ -40,7 +43,10 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) APMRoverMode(APMRoverMode::STEERING ,true), APMRoverMode(APMRoverMode::HOLD ,true), APMRoverMode(APMRoverMode::LOITER ,true), +#if 0 + // Follow me not ready for Stable APMRoverMode(APMRoverMode::FOLLOW ,true), +#endif APMRoverMode(APMRoverMode::SIMPLE ,true), APMRoverMode(APMRoverMode::AUTO ,true), APMRoverMode(APMRoverMode::RTL ,true), diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index 01666b6ba7549c54ce258eb4d9809bcaf53efbfb..1338b3f65b8ea82f69f90fe46dfb392b16844745 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -25,7 +25,10 @@ public: STEERING = 3, HOLD = 4, LOITER = 5, +#if 0 + // Follow me not ready for Stable FOLLOW = 6, +#endif SIMPLE = 7, AUTO = 10, RTL = 11,