Browse Source

mavlink: update submodule

QGC4.4
Beat Küng 3 years ago
parent
commit
150b372095
  1. 2
      libs/mavlink/include/mavlink/v2.0
  2. 8
      src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc
  3. 8
      src/AutoPilotPlugins/PX4/PX4TuningComponent.cc
  4. 16
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  5. 8
      src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc
  6. 8
      src/FirmwarePlugin/APM/APMParameterMetaData.cc
  7. 4
      src/MissionManager/MissionCommandTreeTest.cc
  8. 12
      src/Vehicle/Vehicle.cc
  9. 2
      src/comm/MockLink.cc
  10. 8
      src/comm/QGCMAVLink.cc
  11. 2
      src/comm/QGCMAVLink.h

2
libs/mavlink/include/mavlink/v2.0

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 0b8597ce3ec0f294dcf5e15dbbcd6068ef03eaa2
Subproject commit 6040b0d10ebb253e4d67303286dead636d16fa0f

8
src/AutoPilotPlugins/PX4/PX4FlightBehavior.cc

@ -64,11 +64,11 @@ QUrl PX4FlightBehavior::setupSource() const @@ -64,11 +64,11 @@ QUrl PX4FlightBehavior::setupSource() const
case MAV_TYPE_TRICOPTER:
qmlFile = "qrc:/qml/PX4FlightBehaviorCopter.qml";
break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
qmlFile = "";

8
src/AutoPilotPlugins/PX4/PX4TuningComponent.cc

@ -64,11 +64,11 @@ QUrl PX4TuningComponent::setupSource(void) const @@ -64,11 +64,11 @@ QUrl PX4TuningComponent::setupSource(void) const
case MAV_TYPE_TRICOPTER:
qmlFile = "qrc:/qml/PX4TuningComponentCopter.qml";
break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
qmlFile = "qrc:/qml/PX4TuningComponentVTOL.qml";

16
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -471,11 +471,11 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle) @@ -471,11 +471,11 @@ void APMFirmwarePlugin::initializeVehicle(Vehicle* vehicle)
case MAV_TYPE_HELICOPTER:
vehicle->setFirmwareVersion(3, 6, 0);
break;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING:
@ -671,11 +671,11 @@ QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle) @@ -671,11 +671,11 @@ QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle)
}
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml");
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING:

8
src/FirmwarePlugin/APM/APMFirmwarePluginFactory.cc

@ -46,11 +46,11 @@ FirmwarePlugin* APMFirmwarePluginFactory::firmwarePluginForAutopilot(MAV_AUTOPIL @@ -46,11 +46,11 @@ FirmwarePlugin* APMFirmwarePluginFactory::firmwarePluginForAutopilot(MAV_AUTOPIL
_arduCopterPluginInstance = new ArduCopterFirmwarePlugin;
}
return _arduCopterPluginInstance;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_FIXED_WING:

8
src/FirmwarePlugin/APM/APMParameterMetaData.cc

@ -85,11 +85,11 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) @@ -85,11 +85,11 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
switch(vehicleTypeEnum) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
vehicleName = "ArduPlane";

4
src/MissionManager/MissionCommandTreeTest.cc

@ -203,12 +203,12 @@ void MissionCommandTreeTest::testAllTrees(void) @@ -203,12 +203,12 @@ void MissionCommandTreeTest::testAllTrees(void)
QList<MAV_TYPE> vehicleList;
firmwareList << MAV_AUTOPILOT_GENERIC << MAV_AUTOPILOT_PX4 << MAV_AUTOPILOT_ARDUPILOTMEGA;
vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_QUADROTOR;
vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_TAILSITTER_QUADROTOR;
// This will cause all of the variants of collapsed trees to be built
for(MAV_AUTOPILOT firmwareType: firmwareList) {
for (MAV_TYPE vehicleType: vehicleList) {
if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_QUADROTOR) {
if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_TAILSITTER_QUADROTOR) {
// VTOL in ArduPilot shows up as plane so we can test this pair
continue;
}

12
src/Vehicle/Vehicle.cc

@ -1809,12 +1809,12 @@ int Vehicle::motorCount() @@ -1809,12 +1809,12 @@ int Vehicle::motorCount()
switch (_vehicleType) {
case MAV_TYPE_HELICOPTER:
return 1;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
return 2;
case MAV_TYPE_TRICOPTER:
return 3;
case MAV_TYPE_QUADROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
return 4;
case MAV_TYPE_HEXAROTOR:
return 6;
@ -2431,11 +2431,11 @@ QString Vehicle::vehicleTypeName() const { @@ -2431,11 +2431,11 @@ QString Vehicle::vehicleTypeName() const {
{ MAV_TYPE_FLAPPING_WING, tr("Flapping wing")},
{ MAV_TYPE_KITE, tr("Flapping wing")},
{ MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")},
{ MAV_TYPE_VTOL_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")},
{ MAV_TYPE_VTOL_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")},
{ 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_RESERVED2, tr("VTOL reserved 2")},
{ MAV_TYPE_VTOL_RESERVED3, tr("VTOL reserved 3")},
{ 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_RESERVED5, tr("VTOL reserved 5")},
{ MAV_TYPE_GIMBAL, tr("Onboard gimbal")},

2
src/comm/MockLink.cc

@ -427,7 +427,7 @@ void MockLink::_sendSysStatus(void) @@ -427,7 +427,7 @@ void MockLink::_sendSysStatus(void)
4200 * 4, // voltage_battery
8000, // current_battery
_battery1PctRemaining, // battery_remaining
0,0,0,0,0,0);
0,0,0,0,0,0,0,0,0);
respondWithMavlinkMessage(msg);
}

8
src/comm/QGCMAVLink.cc

@ -125,11 +125,11 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType) @@ -125,11 +125,11 @@ QGCMAVLink::VehicleClass_t QGCMAVLink::vehicleClass(MAV_TYPE mavType)
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
return VehicleClassMultiRotor;
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_FIXEDROTOR:
case MAV_TYPE_VTOL_TAILSITTER:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
return VehicleClassVTOL;

2
src/comm/QGCMAVLink.h

@ -68,7 +68,7 @@ public: @@ -68,7 +68,7 @@ public:
static constexpr VehicleClass_t VehicleClassRoverBoat = MAV_TYPE_GROUND_ROVER;
static constexpr VehicleClass_t VehicleClassSub = MAV_TYPE_SUBMARINE;
static constexpr VehicleClass_t VehicleClassMultiRotor = MAV_TYPE_QUADROTOR;
static constexpr VehicleClass_t VehicleClassVTOL = MAV_TYPE_VTOL_QUADROTOR;
static constexpr VehicleClass_t VehicleClassVTOL = MAV_TYPE_VTOL_TAILSITTER_QUADROTOR;
static constexpr VehicleClass_t VehicleClassGeneric = MAV_TYPE_GENERIC;
static bool isPX4FirmwareClass (MAV_AUTOPILOT autopilot) { return autopilot == MAV_AUTOPILOT_PX4; }

Loading…
Cancel
Save