diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index 6fe216796add2c4e74ae2aebdc878709e5c05cb9..58e79135a552986ea84928bfed3c77721d1ef134 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -100,7 +100,7 @@ QGCView { spacing: _margins * 0.5 anchors.verticalCenter: parent.verticalCenter Row { - visible: !controller.fixedWing + visible: !controller.vehicle.fixedWing QGCLabel { anchors.baseline: lowBattCombo.baseline width: _middleRowWidth @@ -364,7 +364,7 @@ QGCView { sourceSize.width: width mipmap: true fillMode: Image.PreserveAspectFit - source: controller.fixedWing ? "/qmlimages/ReturnToHomeAltitude.svg" : "/qmlimages/ReturnToHomeAltitudeCopter.svg" + source: controller.vehicle.fixedWing ? "/qmlimages/ReturnToHomeAltitude.svg" : "/qmlimages/ReturnToHomeAltitudeCopter.svg" anchors.verticalCenter: parent.verticalCenter } Item { width: _margins * 0.5; height: 1; } @@ -479,7 +479,7 @@ QGCView { sourceSize.width: width mipmap: true fillMode: Image.PreserveAspectFit - source: controller.fixedWing ? "/qmlimages/LandMode.svg" : "/qmlimages/LandModeCopter.svg" + source: controller.vehicle.fixedWing ? "/qmlimages/LandMode.svg" : "/qmlimages/LandModeCopter.svg" anchors.verticalCenter: parent.verticalCenter } Item { diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index c47d3b2ed959136b2e097aa983a32535cf4f2a5a..8dd4180028bc04f8ce563eb973aaab8f36d56a17 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -29,7 +29,7 @@ #include "QGCQmlWidgetHolder.h" #include "SensorsComponentController.h" -// These two list must be kept in sync +const char* SensorsComponent::_airspeedBreaker = "CBRK_AIRSPD_CHK"; SensorsComponent::SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent), @@ -62,7 +62,7 @@ bool SensorsComponent::requiresSetup(void) const bool SensorsComponent::setupComplete(void) const { foreach(const QString &triggerParam, setupCompleteChangedTriggerList()) { - if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { + if (triggerParam != _airspeedBreaker && _autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { return false; } } @@ -74,20 +74,9 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const { QStringList triggers; - triggers << "CAL_MAG0_ID" << "CAL_GYRO0_ID" << "CAL_ACC0_ID"; - switch (_vehicle->vehicleType()) { - case MAV_TYPE_FIXED_WING: - case MAV_TYPE_VTOL_DUOROTOR: - case MAV_TYPE_VTOL_QUADROTOR: - case MAV_TYPE_VTOL_TILTROTOR: - case MAV_TYPE_VTOL_RESERVED2: - case MAV_TYPE_VTOL_RESERVED3: - case MAV_TYPE_VTOL_RESERVED4: - case MAV_TYPE_VTOL_RESERVED5: - triggers << "SENS_DPRES_OFF"; - break; - default: - break; + triggers << "CAL_MAG0_ID" << "CAL_GYRO0_ID" << "CAL_ACC0_ID" << "CBRK_AIRSPD_CHK"; + if (_vehicle->fixedWing() && _autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) { + triggers << "SENS_DPRES_OFF"; } return triggers; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.h b/src/AutoPilotPlugins/PX4/SensorsComponent.h index a0557b44352f1008366c6882fe34332e3c8ce932..36ac7259fc314a0dc0fb3a9c34f4c70404bae565 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.h @@ -53,6 +53,8 @@ public: private: const QString _name; QVariantList _summaryItems; + + static const char* _airspeedBreaker; }; #endif diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.qml b/src/AutoPilotPlugins/PX4/SensorsComponent.qml index f6be8dc0cff65e36a8ffcc186250149b17ef8175..8a3699ae1935e62d02716668b55fd46a33fb1584 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.qml @@ -348,7 +348,7 @@ QGCView { id: airspeedButton width: parent.buttonWidth text: qsTr("Airspeed") - visible: controller.fixedWing + visible: controller.vehicle.fixedWing && controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value != 162128 indicatorGreen: sens_dpres_off.value != 0 onClicked: { diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 82101968b1766d051b4f644214e151ef2df6f4ac..0c14a399d6b821952a2906a0e970b61271319826 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -467,23 +467,6 @@ void SensorsComponentController::_refreshParams(void) _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_"); } -bool SensorsComponentController::fixedWing(void) -{ - switch (_vehicle->vehicleType()) { - case MAV_TYPE_FIXED_WING: - case MAV_TYPE_VTOL_DUOROTOR: - case MAV_TYPE_VTOL_QUADROTOR: - case MAV_TYPE_VTOL_TILTROTOR: - case MAV_TYPE_VTOL_RESERVED2: - case MAV_TYPE_VTOL_RESERVED3: - case MAV_TYPE_VTOL_RESERVED4: - case MAV_TYPE_VTOL_RESERVED5: - return true; - default: - return false; - } -} - void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) { _showOrientationCalArea = show; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.h b/src/AutoPilotPlugins/PX4/SensorsComponentController.h index fe9744efa1a7eb76e646d8b2b792f31c743d361f..399de4b3ba04892bd542ab6e395680070a27e511 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.h @@ -44,8 +44,6 @@ class SensorsComponentController : public FactPanelController public: SensorsComponentController(void); - Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT) - Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog) Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar) @@ -97,8 +95,6 @@ public: Q_INVOKABLE void cancelCalibration(void); Q_INVOKABLE bool usingUDPLink(void); - bool fixedWing(void); - signals: void showGyroCalAreaChanged(void); void showOrientationCalAreaChanged(void); diff --git a/src/FactSystem/FactControls/FactPanelController.h b/src/FactSystem/FactControls/FactPanelController.h index 0c177dbbeb5f538aa3d75ec397a5e12a7f16bd06..878ae8ff72f1aaf0c15fdf419f9bb6b7273ea45e 100644 --- a/src/FactSystem/FactControls/FactPanelController.h +++ b/src/FactSystem/FactControls/FactPanelController.h @@ -46,6 +46,7 @@ public: FactPanelController(void); Q_PROPERTY(QQuickItem* factPanel READ factPanel WRITE setFactPanel) + Q_PROPERTY(Vehicle* vehicle MEMBER _vehicle CONSTANT) Q_INVOKABLE Fact* getParameterFact (int componentId, const QString& name, bool reportMissing = true); Q_INVOKABLE bool parameterExists (int componentId, const QString& name);