diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index 97c50e1..55988d1 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 97c50e128768c9b95c5542b8fc751198b1af96da +Subproject commit 55988d1ec99761b9c5e447a51dcb258161672805 diff --git a/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc b/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc index 1a852e8..3cd44b3 100644 --- a/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc +++ b/src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc @@ -69,7 +69,7 @@ QUrl PX4FlightBehavior::setupSource() const case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: qmlFile = ""; break; diff --git a/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc b/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc index 53c9eae..ec315d5 100644 --- a/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc +++ b/src/AutoPilotPlugins/PX4/PX4TuningComponent.cc @@ -69,7 +69,7 @@ QUrl PX4TuningComponent::setupSource(void) const case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: qmlFile = "qrc:/qml/PX4TuningComponentVTOL.qml"; break; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index d404c70..185a521 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -476,7 +476,7 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: vehicle->setFirmwareVersion(3, 9, 0); @@ -699,7 +699,7 @@ QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: if (vehicle->versionCompare(4, 2, 0) >= 0) { diff --git a/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc b/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc index 7f2cdef..d6b9f1f 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc @@ -51,7 +51,7 @@ FirmwarePlugin* APMFirmwarePluginFactory::firmwarePluginForAutopilot(MAV_AUTOPIL case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: case MAV_TYPE_FIXED_WING: if (!_arduPlanePluginInstance) { diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 78d23cc..4ad0055 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -90,7 +90,7 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: vehicleName = "ArduPlane"; break; diff --git a/src/Vehicle/RemoteIDManager.cc b/src/Vehicle/RemoteIDManager.cc index 11ad0f3..f88fc3a 100644 --- a/src/Vehicle/RemoteIDManager.cc +++ b/src/Vehicle/RemoteIDManager.cc @@ -126,7 +126,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) mavlink_open_drone_id_arm_status_t armStatus; mavlink_msg_open_drone_id_arm_status_decode(&message, &armStatus); - if (armStatus.status == MAV_ODID_GOOD_TO_ARM && !_armStatusGood) { + if (armStatus.status == MAV_ODID_ARM_STATUS_GOOD_TO_ARM && !_armStatusGood) { // If good to arm, even if basic ID is not set on GCS, it was set by remoteID parameters, so GCS one would be optional in this case if (!_basicIDGood) { _basicIDGood = true; @@ -137,7 +137,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) qCDebug(RemoteIDManagerLog) << "Arm status GOOD TO ARM."; } - if (armStatus.status == MAV_ODID_PRE_ARM_FAIL_GENERIC) { + if (armStatus.status == MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC) { _armStatusGood = false; _armStatusError = QString::fromLocal8Bit(armStatus.error); // Check if the error is because of missing basic id diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 1813d7a..91280aa 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2570,14 +2570,14 @@ QString Vehicle::vehicleTypeName() const { { MAV_TYPE_OCTOROTOR, tr("Octorotor")}, { MAV_TYPE_TRICOPTER, tr("Octorotor")}, { MAV_TYPE_FLAPPING_WING, tr("Flapping wing")}, - { MAV_TYPE_KITE, tr("Flapping wing")}, + { MAV_TYPE_KITE, tr("Kite")}, { MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")}, { MAV_TYPE_VTOL_TAILSITTER_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")}, { MAV_TYPE_VTOL_TAILSITTER_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")}, { MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")}, { MAV_TYPE_VTOL_FIXEDROTOR, tr("VTOL Fixedrotor")}, { MAV_TYPE_VTOL_TAILSITTER, tr("VTOL Tailsitter")}, - { MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")}, + { MAV_TYPE_VTOL_TILTWING, tr("VTOL Tiltwing")}, { MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")}, { MAV_TYPE_GIMBAL, tr("Onboard gimbal")}, { MAV_TYPE_ADSB, tr("Onboard ADSB peripheral")}, diff --git a/src/comm/QGCMAVLink.cc b/src/comm/QGCMAVLink.cc index 59f9240..2f20bc2 100644 --- a/src/comm/QGCMAVLink.cc +++ b/src/comm/QGCMAVLink.cc @@ -130,7 +130,7 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType) case MAV_TYPE_VTOL_TILTROTOR: case MAV_TYPE_VTOL_FIXEDROTOR: case MAV_TYPE_VTOL_TAILSITTER: - case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_TILTWING: case MAV_TYPE_VTOL_RESERVED5: return VehicleClassVTOL; case MAV_TYPE_FIXED_WING: