Commit 13000a24 authored by DoinLakeFlyer's avatar DoinLakeFlyer

parent 63ed8565
...@@ -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"}, { GUIDED_NOGPS, "Guided No GPS"},
{ SMART_RTL, "Smart RTL"}, { SMART_RTL, "Smart RTL"},
{ FLOWHOLD, "Flow Hold" }, { FLOWHOLD, "Flow Hold" },
#if 0
// Follow me not ready for Stable
{ FOLLOW, "Follow" }, { FOLLOW, "Follow" },
#endif
{ ZIGZAG, "ZigZag" }, { ZIGZAG, "ZigZag" },
}); });
} }
...@@ -71,7 +74,10 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) ...@@ -71,7 +74,10 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), APMCopterMode(APMCopterMode::GUIDED_NOGPS, true),
APMCopterMode(APMCopterMode::SMART_RTL, true), APMCopterMode(APMCopterMode::SMART_RTL, true),
APMCopterMode(APMCopterMode::FLOWHOLD, true), APMCopterMode(APMCopterMode::FLOWHOLD, true),
#if 0
// Follow me not ready for Stable
APMCopterMode(APMCopterMode::FOLLOW, true), APMCopterMode(APMCopterMode::FOLLOW, true),
#endif
APMCopterMode(APMCopterMode::ZIGZAG, true), APMCopterMode(APMCopterMode::ZIGZAG, true),
}); });
......
...@@ -43,7 +43,10 @@ public: ...@@ -43,7 +43,10 @@ public:
GUIDED_NOGPS= 20, GUIDED_NOGPS= 20,
SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps
FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder 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 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 ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
}; };
......
...@@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable) ...@@ -22,7 +22,10 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
{STEERING, "Steering"}, {STEERING, "Steering"},
{HOLD, "Hold"}, {HOLD, "Hold"},
{LOITER, "Loiter"}, {LOITER, "Loiter"},
#if 0
// Follow me not ready for Stable
{FOLLOW, "Follow"}, {FOLLOW, "Follow"},
#endif
{SIMPLE, "Simple"}, {SIMPLE, "Simple"},
{AUTO, "Auto"}, {AUTO, "Auto"},
{RTL, "RTL"}, {RTL, "RTL"},
...@@ -40,7 +43,10 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) ...@@ -40,7 +43,10 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
APMRoverMode(APMRoverMode::STEERING ,true), APMRoverMode(APMRoverMode::STEERING ,true),
APMRoverMode(APMRoverMode::HOLD ,true), APMRoverMode(APMRoverMode::HOLD ,true),
APMRoverMode(APMRoverMode::LOITER ,true), APMRoverMode(APMRoverMode::LOITER ,true),
#if 0
// Follow me not ready for Stable
APMRoverMode(APMRoverMode::FOLLOW ,true), APMRoverMode(APMRoverMode::FOLLOW ,true),
#endif
APMRoverMode(APMRoverMode::SIMPLE ,true), APMRoverMode(APMRoverMode::SIMPLE ,true),
APMRoverMode(APMRoverMode::AUTO ,true), APMRoverMode(APMRoverMode::AUTO ,true),
APMRoverMode(APMRoverMode::RTL ,true), APMRoverMode(APMRoverMode::RTL ,true),
......
...@@ -25,7 +25,10 @@ public: ...@@ -25,7 +25,10 @@ public:
STEERING = 3, STEERING = 3,
HOLD = 4, HOLD = 4,
LOITER = 5, LOITER = 5,
#if 0
// Follow me not ready for Stable
FOLLOW = 6, FOLLOW = 6,
#endif
SIMPLE = 7, SIMPLE = 7,
AUTO = 10, AUTO = 10,
RTL = 11, RTL = 11,
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment