Commit b2ced878 authored by DonLakeFlyer's avatar DonLakeFlyer
Browse files

Move prerequisiteSetup method to AutopilotPlugin

This makes VehicleComponents reusable from core plugin without
requiring override of prerequisiteSetup
parent 5e9e8b81
......@@ -98,8 +98,3 @@ QUrl APMAirframeComponent::summaryQmlSource(void) const
return QUrl();
}
}
QString APMAirframeComponent::prerequisiteSetup(void) const
{
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private:
bool _requiresFrameSetup; ///< true: FRAME parameter must be set
......
......@@ -137,3 +137,38 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
return _components;
}
QString APMAutoPilotPlugin::prerequisiteSetup(VehicleComponent* component) const
{
bool requiresAirframeCheck = false;
if (qobject_cast<const APMFlightModesComponent*>(component)) {
if (_airframeComponent && !_airframeComponent->setupComplete()) {
return _airframeComponent->name();
}
if (_radioComponent && !_radioComponent->setupComplete()) {
return _radioComponent->name();
}
requiresAirframeCheck = true;
} else if (qobject_cast<const APMRadioComponent*>(component)) {
requiresAirframeCheck = true;
} else if (qobject_cast<const APMCameraComponent*>(component)) {
requiresAirframeCheck = true;
} else if (qobject_cast<const APMPowerComponent*>(component)) {
requiresAirframeCheck = true;
} else if (qobject_cast<const APMSafetyComponent*>(component)) {
requiresAirframeCheck = true;
} else if (qobject_cast<const APMTuningComponent*>(component)) {
requiresAirframeCheck = true;
} else if (qobject_cast<const APMSensorsComponent*>(component)) {
requiresAirframeCheck = true;
}
if (requiresAirframeCheck) {
if (_airframeComponent && !_airframeComponent->setupComplete()) {
return _airframeComponent->name();
}
}
return QString();
}
......@@ -40,28 +40,10 @@ public:
// Overrides from AutoPilotPlugin
const QVariantList& vehicleComponents(void) final;
QString prerequisiteSetup(VehicleComponent* component) const override;
APMAirframeComponent* airframeComponent (void) const { return _airframeComponent; }
APMCameraComponent* cameraComponent (void) const { return _cameraComponent; }
APMLightsComponent* lightsComponent (void) const { return _lightsComponent; }
APMSubFrameComponent* subFrameComponent (void) const { return _subFrameComponent; }
APMFlightModesComponent* flightModesComponent(void) const { return _flightModesComponent; }
APMPowerComponent* powerComponent (void) const { return _powerComponent; }
#if 0
// Temporarily removed, waiting for new command implementation
MotorComponent* motorComponent (void) const { return _motorComponent; }
#endif
APMRadioComponent* radioComponent (void) const { return _radioComponent; }
APMSafetyComponent* safetyComponent (void) const { return _safetyComponent; }
APMSensorsComponent* sensorsComponent (void) const { return _sensorsComponent; }
APMTuningComponent* tuningComponent (void) const { return _tuningComponent; }
ESP8266Component* esp8266Component (void) const { return _esp8266Component; }
MixersComponent* mixersComponent (void) { return _mixersComponent; }
private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
QVariantList _components;
protected:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
APMAirframeComponent* _airframeComponent;
APMCameraComponent* _cameraComponent;
APMLightsComponent* _lightsComponent;
......@@ -79,6 +61,9 @@ private:
APMAirframeLoader* _airframeFacts;
ESP8266Component* _esp8266Component;
MixersComponent* _mixersComponent;
private:
QVariantList _components;
};
#endif
......@@ -61,15 +61,3 @@ QUrl APMCameraComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMCameraComponentSummary.qml"));
}
QString APMCameraComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private:
const QString _name;
......
......@@ -58,19 +58,3 @@ QUrl APMFlightModesComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMFlightModesComponentSummary.qml"));
}
QString APMFlightModesComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
} else if (plugin->radioComponent() != NULL) {
if (!plugin->radioComponent()->setupComplete()) {
return plugin->radioComponent()->name();
}
}
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private:
const QString _name;
......
......@@ -62,8 +62,3 @@ QUrl APMLightsComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMLightsComponentSummary.qml"));
}
QString APMLightsComponent::prerequisiteSetup(void) const
{
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private:
const QString _name;
......
......@@ -62,13 +62,3 @@ QUrl APMPowerComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMPowerComponentSummary.qml"));
}
QString APMPowerComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete (void) const final;
QUrl setupSource (void) const final;
QUrl summaryQmlSource (void) const final;
QString prerequisiteSetup (void) const final;
private:
const QString _name;
......
......@@ -96,17 +96,6 @@ QUrl APMRadioComponent::summaryQmlSource(void) const
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMRadioComponentSummary.qml"));
}
QString APMRadioComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
void APMRadioComponent::_connectSetupTriggers(void)
{
// Disconnect previous triggers
......
......@@ -32,7 +32,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private slots:
void _triggerChanged(void);
......
......@@ -127,15 +127,3 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const
return QUrl::fromUserInput(qmlFile);
}
QString APMSafetyComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
......@@ -31,7 +31,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
bool allowSetupWhileArmed(void) const final { return true; }
private:
......
......@@ -75,18 +75,6 @@ QUrl APMSensorsComponent::summaryQmlSource(void) const
return QUrl::fromUserInput("qrc:/qml/APMSensorsComponentSummary.qml");
}
QString APMSensorsComponent::prerequisiteSetup(void) const
{
APMAutoPilotPlugin* plugin = dynamic_cast<APMAutoPilotPlugin*>(_autopilot);
Q_ASSERT(plugin);
if (!plugin->airframeComponent()->setupComplete()) {
return plugin->airframeComponent()->name();
}
return QString();
}
bool APMSensorsComponent::compassSetupNeeded(void) const
{
const size_t cCompass = 3;
......
......@@ -34,7 +34,6 @@ public:
bool setupComplete(void) const final;
QUrl setupSource(void) const final;
QUrl summaryQmlSource(void) const final;
QString prerequisiteSetup(void) const final;
private:
const QString _name;
......
......@@ -24,7 +24,8 @@ QGC_LOGGING_CATEGORY(APMSensorsComponentControllerVerboseLog, "APMSensorsCompone
const char* APMSensorsComponentController::_compassCalFitnessParam = "COMPASS_CAL_FIT";
APMSensorsComponentController::APMSensorsComponentController(void)
: _statusLog(NULL)
: _sensorsComponent(NULL)
, _statusLog(NULL)
, _progressBar(NULL)
, _compassButton(NULL)
, _accelButton(NULL)
......@@ -68,8 +69,19 @@ APMSensorsComponentController::APMSensorsComponentController(void)
APMAutoPilotPlugin * apmPlugin = qobject_cast<APMAutoPilotPlugin*>(_vehicle->autopilotPlugin());
_sensorsComponent = apmPlugin->sensorsComponent();
connect(_sensorsComponent, &VehicleComponent::setupCompleteChanged, this, &APMSensorsComponentController::setupNeededChanged);
// Find the sensors component
foreach (const QVariant& varVehicleComponent, apmPlugin->vehicleComponents()) {
_sensorsComponent = qobject_cast<APMSensorsComponent*>(varVehicleComponent.value<VehicleComponent*>());
if (_sensorsComponent) {
break;
}
}
if (_sensorsComponent) {
connect(_sensorsComponent, &VehicleComponent::setupCompleteChanged, this, &APMSensorsComponentController::setupNeededChanged);
} else {
qWarning() << "Sensors component is missing";
}
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
}
......
......@@ -64,8 +64,3 @@ QUrl APMSubFrameComponent::summaryQmlSource(void) const
{
return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMSubFrameComponentSummary.qml"));
}
QString APMSubFrameComponent::prerequisiteSetup(void) const
{
return QString();
}
Supports Markdown
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