Commit b97ece01 authored by Don Gagne's avatar Don Gagne

Fix VTOL handling

parent 6af64398
......@@ -31,7 +31,6 @@
APMFlightModesComponentController::APMFlightModesComponentController(void)
: _activeFlightMode(0)
, _channelCount(Vehicle::cMaxRcChannels)
, _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING)
{
QStringList usedParams;
usedParams << QStringLiteral("FLTMODE1") << QStringLiteral("FLTMODE2") << QStringLiteral("FLTMODE3")
......
......@@ -45,7 +45,6 @@ public:
Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(bool fixedWing MEMBER _fixedWing CONSTANT)
int activeFlightMode(void) const { return _activeFlightMode; }
QVariantList channelOptionEnabled(void) const { return _rgChannelOptionEnabled; }
......@@ -61,7 +60,6 @@ private:
int _activeFlightMode;
int _channelCount;
QVariantList _rgChannelOptionEnabled;
bool _fixedWing;
};
#endif
......@@ -430,23 +430,6 @@ void APMSensorsComponentController::_refreshParams(void)
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
}
bool APMSensorsComponentController::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 APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
{
_showOrientationCalArea = show;
......
......@@ -42,8 +42,6 @@ class APMSensorsComponentController : public FactPanelController
public:
APMSensorsComponentController(void);
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT)
Q_PROPERTY(QQuickItem* statusLog MEMBER _statusLog)
Q_PROPERTY(QQuickItem* progressBar MEMBER _progressBar)
......@@ -93,8 +91,6 @@ public:
Q_INVOKABLE void cancelCalibration(void);
Q_INVOKABLE void nextClicked(void);
bool fixedWing(void);
bool compassSetupNeeded(void) const;
bool accelSetupNeeded(void) const;
......
......@@ -61,7 +61,7 @@ PX4AdvancedFlightModesController::PX4AdvancedFlightModesController(void) :
void PX4AdvancedFlightModesController::_init(void)
{
// FIXME: What about VTOL? That confuses the whole Flight Mode naming scheme
_fixedWing = _vehicle->vehicleType() == MAV_TYPE_FIXED_WING;
_fixedWing = _vehicle->fixedWing();
// We need to know min and max for channel in order to calculate percentage range
for (int channel=0; channel<_chanMax; channel++) {
......
......@@ -75,7 +75,7 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const
QStringList triggers;
triggers << "CAL_MAG0_ID" << "CAL_GYRO0_ID" << "CAL_ACC0_ID" << "CBRK_AIRSPD_CHK";
if (_vehicle->fixedWing() && _autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
if ((_vehicle->fixedWing() || _vehicle->vtol()) && _autopilot->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
triggers << "SENS_DPRES_OFF";
}
......@@ -91,16 +91,10 @@ QUrl SensorsComponent::summaryQmlSource(void) const
{
QString summaryQml;
switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml";
break;
default:
summaryQml = "qrc:/qml/SensorsComponentSummary.qml";
break;
if (_vehicle->fixedWing() || _vehicle->vtol()) {
summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml";
} else {
summaryQml = "qrc:/qml/SensorsComponentSummary.qml";
}
return QUrl::fromUserInput(summaryQml);
......
......@@ -348,7 +348,7 @@ QGCView {
id: airspeedButton
width: parent.buttonWidth
text: qsTr("Airspeed")
visible: controller.vehicle.fixedWing && controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value != 162128
visible: (controller.vehicle.fixedWing || controller.vehicle.vtol) && controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value != 162128
indicatorGreen: sens_dpres_off.value != 0
onClicked: {
......
......@@ -1445,6 +1445,22 @@ bool Vehicle::multiRotor(void) const
}
}
bool Vehicle::vtol(void) const
{
switch (vehicleType()) {
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 Vehicle::_setCoordinateValid(bool coordinateValid)
{
if (coordinateValid != _coordinateValid) {
......
......@@ -285,6 +285,7 @@ public:
Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
Q_PROPERTY(bool fixedWing READ fixedWing CONSTANT)
Q_PROPERTY(bool multiRotor READ multiRotor CONSTANT)
Q_PROPERTY(bool vtol READ vtol CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
......@@ -457,6 +458,7 @@ public:
bool fixedWing(void) const;
bool multiRotor(void) const;
bool vtol(void) const;
void setFlying(bool flying);
void setGuidedMode(bool guidedMode);
......
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