From 288e2ae3244c2d30445e9fb2de23c9c3a249da4a Mon Sep 17 00:00:00 2001 From: DoinLakeFlyer Date: Tue, 25 Feb 2020 10:46:49 -0800 Subject: [PATCH] Remove ArduPilot Follow Me support from Stable --- src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc | 7 +++++++ src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h | 3 +++ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc | 3 +++ src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h | 3 +++ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc | 3 +++ src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h | 3 +++ 6 files changed, 22 insertions(+) diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 595340707..5209e1065 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) , _tuningComponent (nullptr) , _esp8266Component (nullptr) , _heliComponent (nullptr) +#if 0 + // Follow me not ready for Stable , _followComponent (nullptr) +#endif { #if !defined(NO_SERIAL_LINK) && !defined(__android__) connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack); @@ -104,12 +107,16 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) _safetyComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); +#if 0 + // Follow me not ready for Stable + if ((qobject_cast(_vehicle->firmwarePlugin()) || qobject_cast(_vehicle->firmwarePlugin())) && _vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) { _followComponent = new APMFollowComponent(_vehicle, this); _followComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_followComponent)); } +#endif if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) { _heliComponent = new APMHeliComponent(_vehicle, this); diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h index 28f2166bc..410fb8be0 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h @@ -57,7 +57,10 @@ protected: APMTuningComponent* _tuningComponent; ESP8266Component* _esp8266Component; APMHeliComponent* _heliComponent; +#if 0 + // Follow me not ready for Stable APMFollowComponent* _followComponent; +#endif #if !defined(NO_SERIAL_LINK) && !defined(__android__) private slots: diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 6038b81a8..21cb15446 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -141,7 +141,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* return true; } +#if 0 + // Follow me not ready for Stable void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) { _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); } +#endif diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 9b802a806..bd87214a9 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -71,7 +71,10 @@ public: bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override; QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } bool supportsSmartRTL (void) const override { return true; } +#if 0 + // Follow me not ready for Stable void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; +#endif private: static bool _remapParamNameIntialized; diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index 46a0fe001..c5e9376ee 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -78,7 +78,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) return true; } +#if 0 + // Follow me not ready for Stable void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) { _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); } +#endif diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index ca29f890f..01666b6ba 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -53,7 +53,10 @@ public: bool supportsNegativeThrust (Vehicle *) final; bool supportsSmartRTL (void) const override { return true; } QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); } +#if 0 + // Follow me not ready for Stable void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override; +#endif private: static bool _remapParamNameIntialized; -- 2.22.0