Commit cd5b02c0 authored by Don Gagne's avatar Don Gagne

Merge pull request #3392 from DonLakeFlyer/SensorSafety

Sensor/Safety panel fixes
parents b8d25964 b073e9fe
......@@ -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 {
......
......@@ -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;
......
......@@ -53,6 +53,8 @@ public:
private:
const QString _name;
QVariantList _summaryItems;
static const char* _airspeedBreaker;
};
#endif
......@@ -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: {
......
......@@ -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;
......
......@@ -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);
......
......@@ -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);
......
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