Commit 288e2ae3 authored by DoinLakeFlyer's avatar DoinLakeFlyer

parent 3cb4f124
...@@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) ...@@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent)
, _tuningComponent (nullptr) , _tuningComponent (nullptr)
, _esp8266Component (nullptr) , _esp8266Component (nullptr)
, _heliComponent (nullptr) , _heliComponent (nullptr)
#if 0
// Follow me not ready for Stable
, _followComponent (nullptr) , _followComponent (nullptr)
#endif
{ {
#if !defined(NO_SERIAL_LINK) && !defined(__android__) #if !defined(NO_SERIAL_LINK) && !defined(__android__)
connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack); connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack);
...@@ -104,12 +107,16 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -104,12 +107,16 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_safetyComponent->setupTriggerSignals(); _safetyComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_safetyComponent));
#if 0
// Follow me not ready for Stable
if ((qobject_cast<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) || qobject_cast<ArduRoverFirmwarePlugin*>(_vehicle->firmwarePlugin())) && if ((qobject_cast<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) || qobject_cast<ArduRoverFirmwarePlugin*>(_vehicle->firmwarePlugin())) &&
_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) { _vehicle->parameterManager()->parameterExists(-1, QStringLiteral("FOLL_ENABLE"))) {
_followComponent = new APMFollowComponent(_vehicle, this); _followComponent = new APMFollowComponent(_vehicle, this);
_followComponent->setupTriggerSignals(); _followComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_followComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_followComponent));
} }
#endif
if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) { if (_vehicle->vehicleType() == MAV_TYPE_HELICOPTER && (_vehicle->versionCompare(4, 0, 0) >= 0)) {
_heliComponent = new APMHeliComponent(_vehicle, this); _heliComponent = new APMHeliComponent(_vehicle, this);
......
...@@ -57,7 +57,10 @@ protected: ...@@ -57,7 +57,10 @@ protected:
APMTuningComponent* _tuningComponent; APMTuningComponent* _tuningComponent;
ESP8266Component* _esp8266Component; ESP8266Component* _esp8266Component;
APMHeliComponent* _heliComponent; APMHeliComponent* _heliComponent;
#if 0
// Follow me not ready for Stable
APMFollowComponent* _followComponent; APMFollowComponent* _followComponent;
#endif
#if !defined(NO_SERIAL_LINK) && !defined(__android__) #if !defined(NO_SERIAL_LINK) && !defined(__android__)
private slots: private slots:
......
...@@ -141,7 +141,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* ...@@ -141,7 +141,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
return true; return true;
} }
#if 0
// Follow me not ready for Stable
void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif
...@@ -71,7 +71,10 @@ public: ...@@ -71,7 +71,10 @@ public:
bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override; bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); }
bool supportsSmartRTL (void) const override { return true; } 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; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;
......
...@@ -78,7 +78,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) ...@@ -78,7 +78,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/)
return true; return true;
} }
#if 0
// Follow me not ready for Stable
void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) void ArduRoverFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities)
{ {
_sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities); _sendGCSMotionReport(vehicle, motionReport, estimatationCapabilities);
} }
#endif
...@@ -53,7 +53,10 @@ public: ...@@ -53,7 +53,10 @@ public:
bool supportsNegativeThrust (Vehicle *) final; bool supportsNegativeThrust (Vehicle *) final;
bool supportsSmartRTL (void) const override { return true; } bool supportsSmartRTL (void) const override { return true; }
QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Rover.OfflineEditing.params"); } 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; void sendGCSMotionReport (Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) override;
#endif
private: private:
static bool _remapParamNameIntialized; static bool _remapParamNameIntialized;
......
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