Browse Source

Add airspeed sensor to airship (#9235)

QGC4.4
Anton Erasmus 4 years ago committed by GitHub
parent
commit
f3e48e718d
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 6
      src/AutoPilotPlugins/PX4/SensorsComponent.cc
  2. 2
      src/AutoPilotPlugins/PX4/SensorsSetup.qml
  3. 9
      src/Vehicle/Vehicle.cc
  4. 2
      src/Vehicle/Vehicle.h
  5. 2
      src/api/QGCCorePlugin.cc
  6. 10
      src/comm/QGCMAVLink.cc
  7. 2
      src/comm/QGCMAVLink.h

6
src/AutoPilotPlugins/PX4/SensorsComponent.cc

@ -65,7 +65,7 @@ bool SensorsComponent::setupComplete(void) const @@ -65,7 +65,7 @@ bool SensorsComponent::setupComplete(void) const
return false;
}
if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_vehicle->fixedWing() || _vehicle->vtol() || _vehicle->airship()) {
if (!_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedDisabledParam)->rawValue().toBool() &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedBreakerParam)->rawValue().toInt() != 162128 &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedCalParam)->rawValue().toFloat() == 0.0f) {
@ -81,7 +81,7 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const @@ -81,7 +81,7 @@ QStringList SensorsComponent::setupCompleteChangedTriggerList(void) const
QStringList triggers;
triggers << _deviceIds << _magCalParam << _magEnabledParam;
if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_vehicle->fixedWing() || _vehicle->vtol() || _vehicle->airship()) {
triggers << _airspeedCalParam << _airspeedBreakerParam;
}
@ -97,7 +97,7 @@ QUrl SensorsComponent::summaryQmlSource(void) const @@ -97,7 +97,7 @@ QUrl SensorsComponent::summaryQmlSource(void) const
{
QString summaryQml;
if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_vehicle->fixedWing() || _vehicle->vtol() || _vehicle->airship()) {
summaryQml = "qrc:/qml/SensorsComponentSummaryFixedWing.qml";
} else {
summaryQml = "qrc:/qml/SensorsComponentSummary.qml";

2
src/AutoPilotPlugins/PX4/SensorsSetup.qml

@ -458,7 +458,7 @@ Item { @@ -458,7 +458,7 @@ Item {
id: airspeedButton
width: _buttonWidth
text: qsTr("Airspeed")
visible: (controller.vehicle.fixedWing || controller.vehicle.vtol) &&
visible: (controller.vehicle.fixedWing || controller.vehicle.vtol || controller.vehicle.airship) &&
controller.getParameterFact(-1, "FW_ARSP_MODE").value == 0 &&
controller.getParameterFact(-1, "CBRK_AIRSPD_CHK").value !== 162128 &&
QGroundControl.corePlugin.options.showSensorCalibrationAirspeed &&

9
src/Vehicle/Vehicle.cc

@ -518,7 +518,9 @@ QString Vehicle::firmwareTypeString() const @@ -518,7 +518,9 @@ QString Vehicle::firmwareTypeString() const
QString Vehicle::vehicleTypeString() const
{
if (fixedWing()) {
if (airship()) {
return tr("Airship");
} else if (fixedWing()) {
return tr("Fixed Wing");
} else if (multiRotor()) {
return tr("Multi-Rotor");
@ -2150,6 +2152,11 @@ void Vehicle::_say(const QString& text) @@ -2150,6 +2152,11 @@ void Vehicle::_say(const QString& text)
_toolbox->audioOutput()->say(text.toLower());
}
bool Vehicle::airship() const
{
return QGCMAVLink::isAirship(vehicleType());
}
bool Vehicle::fixedWing() const
{
return QGCMAVLink::isFixedWing(vehicleType());

2
src/Vehicle/Vehicle.h

@ -173,6 +173,7 @@ public: @@ -173,6 +173,7 @@ public:
Q_PROPERTY(uint messagesReceived READ messagesReceived NOTIFY messagesReceivedChanged)
Q_PROPERTY(uint messagesSent READ messagesSent NOTIFY messagesSentChanged)
Q_PROPERTY(uint messagesLost READ messagesLost NOTIFY messagesLostChanged)
Q_PROPERTY(bool airship READ airship NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool fixedWing READ fixedWing NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool multiRotor READ multiRotor NOTIFY vehicleTypeChanged)
Q_PROPERTY(bool vtol READ vtol NOTIFY vehicleTypeChanged)
@ -452,6 +453,7 @@ public: @@ -452,6 +453,7 @@ public:
QString flightMode () const;
void setFlightMode (const QString& flightMode);
bool airship() const;
bool fixedWing() const;
bool multiRotor() const;
bool vtol() const;

2
src/api/QGCCorePlugin.cc

@ -293,7 +293,7 @@ void QGCCorePlugin::factValueGridCreateDefaultSettings(const QString& defaultSet @@ -293,7 +293,7 @@ void QGCCorePlugin::factValueGridCreateDefaultSettings(const QString& defaultSet
{
HorizontalFactValueGrid factValueGrid(defaultSettingsGroup);
bool includeFWValues = factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassFixedWing || factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassVTOL;
bool includeFWValues = factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassFixedWing || factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassVTOL || factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassAirship;
factValueGrid.setFontSize(FactValueGrid::LargeFontSize);

10
src/comm/QGCMAVLink.cc

@ -16,6 +16,7 @@ constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassPX4; @@ -16,6 +16,7 @@ constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassPX4;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassArduPilot;
constexpr QGCMAVLink::FirmwareClass_t QGCMAVLink::FirmwareClassGeneric;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassAirship;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassFixedWing;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassRoverBoat;
constexpr QGCMAVLink::VehicleClass_t QGCMAVLink::VehicleClassSub;
@ -79,6 +80,11 @@ QString QGCMAVLink::firmwareClassToString(FirmwareClass_t firmwareClass) @@ -79,6 +80,11 @@ QString QGCMAVLink::firmwareClassToString(FirmwareClass_t firmwareClass)
}
}
bool QGCMAVLink::isAirship(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassAirship;
}
bool QGCMAVLink::isFixedWing(MAV_TYPE mavType)
{
return vehicleClass(mavType) == VehicleClassFixedWing;
@ -129,6 +135,8 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType) @@ -129,6 +135,8 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType)
return VehicleClassVTOL;
case MAV_TYPE_FIXED_WING:
return VehicleClassFixedWing;
case MAV_TYPE_AIRSHIP:
return VehicleClassAirship;
default:
return VehicleClassGeneric;
}
@ -137,6 +145,8 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType) @@ -137,6 +145,8 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType)
QString QGCMAVLink::vehicleClassToString(VehicleClass_t vehicleClass)
{
switch (vehicleClass) {
case VehicleClassAirship:
return QT_TRANSLATE_NOOP("Vehicle Class", "Airship");
case VehicleClassFixedWing:
return QT_TRANSLATE_NOOP("Vehicle Class", "Fixed Wing");
case VehicleClassRoverBoat:

2
src/comm/QGCMAVLink.h

@ -63,6 +63,7 @@ public: @@ -63,6 +63,7 @@ public:
static constexpr FirmwareClass_t FirmwareClassArduPilot = MAV_AUTOPILOT_ARDUPILOTMEGA;
static constexpr FirmwareClass_t FirmwareClassGeneric = MAV_AUTOPILOT_GENERIC;
static constexpr VehicleClass_t VehicleClassAirship = MAV_TYPE_AIRSHIP;
static constexpr VehicleClass_t VehicleClassFixedWing = MAV_TYPE_FIXED_WING;
static constexpr VehicleClass_t VehicleClassRoverBoat = MAV_TYPE_GROUND_ROVER;
static constexpr VehicleClass_t VehicleClassSub = MAV_TYPE_SUBMARINE;
@ -78,6 +79,7 @@ public: @@ -78,6 +79,7 @@ public:
static QString firmwareClassToString (FirmwareClass_t firmwareClass);
static QList<FirmwareClass_t> allFirmwareClasses (void);
static bool isAirship (MAV_TYPE mavType);
static bool isFixedWing (MAV_TYPE mavType);
static bool isRoverBoat (MAV_TYPE mavType);
static bool isSub (MAV_TYPE mavType);

Loading…
Cancel
Save