diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index e5ba76c473292b28e317c23e6a08263d68407f61..10e5abbad5b03b8cfc6968871701342ef3c8dd47 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -23,50 +23,56 @@ APMCopterMode::APMCopterMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) { setEnumToStringMapping({ - {STABILIZE, "Stabilize"}, - {ACRO, "Acro"}, - {ALT_HOLD, "Altitude Hold"}, - {AUTO, "Auto"}, - {GUIDED, "Guided"}, - {LOITER, "Loiter"}, - {RTL, "RTL"}, - {CIRCLE, "Circle"}, - {LAND, "Land"}, - {DRIFT, "Drift"}, - {SPORT, "Sport"}, - {FLIP, "Flip"}, - {AUTOTUNE, "Autotune"}, - {POS_HOLD, "Position Hold"}, - {BRAKE, "Brake"}, - {THROW, "Throw"}, - {AVOID_ADSB, "Avoid ADSB"}, - {GUIDED_NOGPS, "Guided No GPS"}, - {SAFE_RTL, "Smart RTL"}, + { STABILIZE, "Stabilize"}, + { ACRO, "Acro"}, + { ALT_HOLD, "Altitude Hold"}, + { AUTO, "Auto"}, + { GUIDED, "Guided"}, + { LOITER, "Loiter"}, + { RTL, "RTL"}, + { CIRCLE, "Circle"}, + { LAND, "Land"}, + { DRIFT, "Drift"}, + { SPORT, "Sport"}, + { FLIP, "Flip"}, + { AUTOTUNE, "Autotune"}, + { POS_HOLD, "Position Hold"}, + { BRAKE, "Brake"}, + { THROW, "Throw"}, + { AVOID_ADSB, "Avoid ADSB"}, + { GUIDED_NOGPS, "Guided No GPS"}, + { SMART_RTL, "Smart RTL"}, + { FLOWHOLD, "Flow Hold" }, + { FOLLOW, "Follow Vehicle" }, + { ZIGZAG, "ZigZag" }, }); } ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) { setSupportedModes({ - APMCopterMode(APMCopterMode::STABILIZE ,true), - APMCopterMode(APMCopterMode::ACRO ,true), - APMCopterMode(APMCopterMode::ALT_HOLD ,true), - APMCopterMode(APMCopterMode::AUTO ,true), - APMCopterMode(APMCopterMode::GUIDED ,true), - APMCopterMode(APMCopterMode::LOITER ,true), - APMCopterMode(APMCopterMode::RTL ,true), - APMCopterMode(APMCopterMode::CIRCLE ,true), - APMCopterMode(APMCopterMode::LAND ,true), - APMCopterMode(APMCopterMode::DRIFT ,true), - APMCopterMode(APMCopterMode::SPORT ,true), - APMCopterMode(APMCopterMode::FLIP ,true), - APMCopterMode(APMCopterMode::AUTOTUNE ,true), - APMCopterMode(APMCopterMode::POS_HOLD ,true), - APMCopterMode(APMCopterMode::BRAKE ,true), - APMCopterMode(APMCopterMode::THROW ,true), - APMCopterMode(APMCopterMode::AVOID_ADSB,true), - APMCopterMode(APMCopterMode::GUIDED_NOGPS,true), - APMCopterMode(APMCopterMode::SAFE_RTL,true), + APMCopterMode(APMCopterMode::STABILIZE, true), + APMCopterMode(APMCopterMode::ACRO, true), + APMCopterMode(APMCopterMode::ALT_HOLD, true), + APMCopterMode(APMCopterMode::AUTO, true), + APMCopterMode(APMCopterMode::GUIDED, true), + APMCopterMode(APMCopterMode::LOITER, true), + APMCopterMode(APMCopterMode::RTL, true), + APMCopterMode(APMCopterMode::CIRCLE, true), + APMCopterMode(APMCopterMode::LAND, true), + APMCopterMode(APMCopterMode::DRIFT, true), + APMCopterMode(APMCopterMode::SPORT, true), + APMCopterMode(APMCopterMode::FLIP, true), + APMCopterMode(APMCopterMode::AUTOTUNE, true), + APMCopterMode(APMCopterMode::POS_HOLD, true), + APMCopterMode(APMCopterMode::BRAKE, true), + APMCopterMode(APMCopterMode::THROW, true), + APMCopterMode(APMCopterMode::AVOID_ADSB, true), + APMCopterMode(APMCopterMode::GUIDED_NOGPS, true), + APMCopterMode(APMCopterMode::SMART_RTL, true), + APMCopterMode(APMCopterMode::FLOWHOLD, true), + APMCopterMode(APMCopterMode::FOLLOW, true), + APMCopterMode(APMCopterMode::ZIGZAG, true), }); if (!_remapParamNameIntialized) { diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 563baf7b68fd7db0c300ecfbf24c94257cd574a2..a675e74a4a8f516d67bec0932d1ea5fe93315905 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -41,9 +41,11 @@ public: THROW = 18, AVOID_ADSB = 19, GUIDED_NOGPS= 20, - SAFE_RTL = 21, //Safe Return to Launch + SMART_RTL = 21, // SMART_RTL returns to home by retracing its steps + FLOWHOLD = 22, // FLOWHOLD holds position with optical flow without rangefinder + FOLLOW = 23, // follow attempts to follow another vehicle or ground station + ZIGZAG = 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B }; - static const int modeCount = 22; APMCopterMode(uint32_t mode, bool settable); }; diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h index cd0ce2e8559353ac394e314f307f8fd535fc47e5..0094a669dc441e98ba3896df77b9536a8dd80084 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h @@ -42,7 +42,6 @@ public: QLOITER = 19, QLAND = 20, QRTL = 21, - modeCount }; APMPlaneMode(uint32_t mode, bool settable); diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index 6dd7882562f9ccc694842fb76cbcf784923a8614..ad17a034ccdcb5c39939c45facdb95d121b54db1 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -33,7 +33,6 @@ public: GUIDED = 15, INITIALIZING = 16, }; - static const int modeCount = 17; APMRoverMode(uint32_t mode, bool settable); }; diff --git a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h index b826c1e0c92bd4bd505f93167962a20fbc9445d6..7f6426b07037fd0e7965d7de9c4daa778e24aade 100644 --- a/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduSubFirmwarePlugin.h @@ -96,7 +96,6 @@ public: RESERVED_18 = 18, MANUAL = 19 }; - static const int modeCount = 20; APMSubMode(uint32_t mode, bool settable); }; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index eaa65792e629ae69582bc9f38540dd655aced5f2..c56c477d6b58d68ce86f577554c069bc196738f1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3041,7 +3041,7 @@ void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord) if (!coordinate().isValid()) { return; } - double maxDistance = 1000.0; + double maxDistance = 10000.0; if (coordinate().distanceTo(gotoCoord) > maxDistance) { qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString())); return;