|
|
|
@ -22,10 +22,7 @@ APMRoverMode::APMRoverMode(uint32_t mode, bool settable)
@@ -22,10 +22,7 @@ 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"}, |
|
|
|
@ -43,10 +40,7 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void)
@@ -43,10 +40,7 @@ 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), |
|
|
|
|