Browse Source

Remove some more Follow stuff

QGC4.4
DoinLakeFlyer 5 years ago
parent
commit
13000a24b9
  1. 6
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  2. 3
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
  3. 6
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
  4. 3
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

6
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -43,7 +43,10 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : @@ -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) @@ -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),
});

3
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h

@ -43,7 +43,10 @@ public: @@ -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
};

6
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc

@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) @@ -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) @@ -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),

3
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

@ -25,7 +25,10 @@ public: @@ -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,

Loading…
Cancel
Save