Browse Source

Merge pull request #8414 from DonLakeFlyer/RemoveFollow

Remove ArduPilot Follow Me support from Stable
QGC4.4
Don Gagne 5 years ago committed by GitHub
parent
commit
63ed8565bf
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 7
      src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc
  2. 3
      src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h
  3. 3
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
  4. 3
      src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
  5. 3
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc
  6. 3
      src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

7
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc

@ -53,7 +53,10 @@ APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent) @@ -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) @@ -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<ArduCopterFirmwarePlugin*>(_vehicle->firmwarePlugin()) || qobject_cast<ArduRoverFirmwarePlugin*>(_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);

3
src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h

@ -57,7 +57,10 @@ protected: @@ -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:

3
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc

@ -141,7 +141,10 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* @@ -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

3
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h

@ -71,7 +71,10 @@ public: @@ -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;

3
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc

@ -78,7 +78,10 @@ bool ArduRoverFirmwarePlugin::supportsNegativeThrust(Vehicle* /*vehicle*/) @@ -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

3
src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h

@ -53,7 +53,10 @@ public: @@ -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;

Loading…
Cancel
Save