diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 5953407073412def3eb8f5933a7eb110c68bbb31..5209e106597d2d04e1e3956148eec0e45359c595 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 28f2166bc22626d78ff715e24c1be19c43fc7def..410fb8be02a939051c438e526672fd4e43c5c1d0 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 6038b81a8f51897d676ce7c67705ca495fe53f28..21cb154468a816d5a252a9db3636bf6a62ec0209 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 9b802a80659bf3f036610ffafa1dc301bfc006fb..bd87214a9a33f01cebe5758b8454d4b9bce8a74b 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 46a0fe0011702b967db1abf6c33344f5fe5bfe86..c5e9376eec8396b3cf62686a4a326a543b915626 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 ca29f890ff40fbb46a9f6d76162494689aaab314..01666b6ba7549c54ce258eb4d9809bcaf53efbfb 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;