QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCMAVLink.cc
Go to the documentation of this file.
1#include "QGCMAVLink.h"
2#include "MAVLinkLib.h"
4
5#include <QtCore/QCoreApplication>
6
7QGC_LOGGING_CATEGORY(QGCMAVLinkLog, "MAVLink.QGCMAVLink")
8
9const QHash<int, QString> QGCMAVLink::mavlinkCompIdHash {
10 { MAV_COMP_ID_AUTOPILOT1, "Autopilot" },
11 { MAV_COMP_ID_ONBOARD_COMPUTER, "Onboard Computer" },
12 { MAV_COMP_ID_CAMERA, "Camera1" },
13 { MAV_COMP_ID_CAMERA2, "Camera2" },
14 { MAV_COMP_ID_CAMERA3, "Camera3" },
15 { MAV_COMP_ID_CAMERA4, "Camera4" },
16 { MAV_COMP_ID_CAMERA5, "Camera5" },
17 { MAV_COMP_ID_CAMERA6, "Camera6" },
18 { MAV_COMP_ID_SERVO1, "Servo1" },
19 { MAV_COMP_ID_SERVO2, "Servo2" },
20 { MAV_COMP_ID_SERVO3, "Servo3" },
21 { MAV_COMP_ID_SERVO4, "Servo4" },
22 { MAV_COMP_ID_SERVO5, "Servo5" },
23 { MAV_COMP_ID_SERVO6, "Servo6" },
24 { MAV_COMP_ID_SERVO7, "Servo7" },
25 { MAV_COMP_ID_SERVO8, "Servo8" },
26 { MAV_COMP_ID_SERVO9, "Servo9" },
27 { MAV_COMP_ID_SERVO10, "Servo10" },
28 { MAV_COMP_ID_SERVO11, "Servo11" },
29 { MAV_COMP_ID_SERVO12, "Servo12" },
30 { MAV_COMP_ID_SERVO13, "Servo13" },
31 { MAV_COMP_ID_SERVO14, "Servo14" },
32 { MAV_COMP_ID_GIMBAL, "Gimbal1" },
33 { MAV_COMP_ID_ADSB, "ADSB" },
34 { MAV_COMP_ID_OSD, "OSD" },
35 { MAV_COMP_ID_FLARM, "FLARM" },
36 { MAV_COMP_ID_GIMBAL2, "Gimbal2" },
37 { MAV_COMP_ID_GIMBAL3, "Gimbal3" },
38 { MAV_COMP_ID_GIMBAL4, "Gimbal4" },
39 { MAV_COMP_ID_GIMBAL5, "Gimbal5" },
40 { MAV_COMP_ID_GIMBAL6, "Gimbal6" },
41 { MAV_COMP_ID_IMU, "IMU1" },
42 { MAV_COMP_ID_IMU_2, "IMU2" },
43 { MAV_COMP_ID_IMU_3, "IMU3" },
44 { MAV_COMP_ID_GPS, "GPS1" },
45 { MAV_COMP_ID_GPS2, "GPS2" }
46};
47
48#ifdef MAVLINK_EXTERNAL_RX_STATUS
50#endif
51
52#ifdef MAVLINK_GET_CHANNEL_STATUS
53mavlink_status_t* mavlink_get_channel_status(uint8_t channel)
54{
55#ifndef MAVLINK_EXTERNAL_RX_STATUS
56 static QList<mavlink_status_t> m_mavlink_status(MAVLINK_COMM_NUM_BUFFERS);
57#endif
58 if (!QGCMAVLink::isValidChannel(channel)) {
59 qCWarning(QGCMAVLinkLog) << Q_FUNC_INFO << "Invalid Channel Number:" << channel;
60 return nullptr;
61 }
62
63 return &m_mavlink_status[channel];
64}
65#endif
66
67QGCMAVLink::QGCMAVLink(QObject *parent)
68 : QObject(parent)
69{
70 // qCDebug(StatusTextHandlerLog) << Q_FUNC_INFO << this;
71
72 (void) qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
73 // Removes dependence on Q_ENUM_NS static-init order for queued connections.
74 (void) qRegisterMetaType<GRIPPER_ACTIONS>("GRIPPER_ACTIONS");
75}
76
78{
79 // qCDebug(StatusTextHandlerLog) << Q_FUNC_INFO << this;
80}
81
82QList<QGCMAVLink::FirmwareClass_t> QGCMAVLink::allFirmwareClasses(void)
83{
84 static const QList<QGCMAVLink::FirmwareClass_t> classes = {
88 };
89
90 return classes;
91}
92
93QList<QGCMAVLink::VehicleClass_t> QGCMAVLink::allVehicleClasses(void)
94{
95 static const QList<QGCMAVLink::VehicleClass_t> classes = {
102 };
103
104 return classes;
105}
106
108{
109 if (isPX4FirmwareClass(autopilot)) {
110 return FirmwareClassPX4;
111 } else if (isArduPilotFirmwareClass(autopilot)) {
113 } else {
115 }
116}
117
119{
120 switch (firmwareClass) {
121 case FirmwareClassPX4:
122 return QCoreApplication::translate("Firmware Class", "PX4 Pro");
124 return QCoreApplication::translate("Firmware Class", "ArduPilot");
126 return QCoreApplication::translate("Firmware Class", "Generic");
127 default:
128 return QCoreApplication::translate("Firmware Class", "Unknown");
129 }
130}
131
133{
134 switch (firmwareClass) {
135 case FirmwareClassPX4:
136 return "PX4 Pro";
138 return "ArduPilot";
140 return "Generic";
141 default:
142 return "Unknown";
143 }
144}
145
146MAV_AUTOPILOT QGCMAVLink::firmwareTypeFromString(const QString &firmwareTypeStr)
147{
148 const QString type = firmwareTypeStr.trimmed();
149 if (type == QLatin1String("ArduPilot")) {
150 return MAV_AUTOPILOT_ARDUPILOTMEGA;
151 }
152 if (type == QLatin1String("PX4 Pro")) {
153 return MAV_AUTOPILOT_PX4;
154 }
155 return MAV_AUTOPILOT_GENERIC;
156}
157
158bool QGCMAVLink::isAirship(MAV_TYPE mavType)
159{
160 return vehicleClass(mavType) == VehicleClassAirship;
161}
162
163bool QGCMAVLink::isFixedWing(MAV_TYPE mavType)
164{
165 return vehicleClass(mavType) == VehicleClassFixedWing;
166}
167
168bool QGCMAVLink::isRoverBoat(MAV_TYPE mavType)
169{
170 return vehicleClass(mavType) == VehicleClassRoverBoat;
171}
172
173bool QGCMAVLink::isSpacecraft(MAV_TYPE mavType)
174{
175 return vehicleClass(mavType) == VehicleClassSpacecraft;
176}
177
178bool QGCMAVLink::isSub(MAV_TYPE mavType)
179{
180 return vehicleClass(mavType) == VehicleClassSub;
181}
182
183bool QGCMAVLink::isMultiRotor(MAV_TYPE mavType)
184{
185 return vehicleClass(mavType) == VehicleClassMultiRotor;
186}
187
188bool QGCMAVLink::isVTOL(MAV_TYPE mavType)
189{
190 return vehicleClass(mavType) == VehicleClassVTOL;
191}
192
194{
195 switch (mavType) {
196 case MAV_TYPE_GROUND_ROVER:
197 case MAV_TYPE_SURFACE_BOAT:
199 case MAV_TYPE_SUBMARINE:
200 return VehicleClassSub;
201 case MAV_TYPE_SPACECRAFT_ORBITER:
203 case MAV_TYPE_QUADROTOR:
204 case MAV_TYPE_COAXIAL:
205 case MAV_TYPE_HELICOPTER:
206 case MAV_TYPE_HEXAROTOR:
207 case MAV_TYPE_OCTOROTOR:
208 case MAV_TYPE_TRICOPTER:
210 case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
211 case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
212 case MAV_TYPE_VTOL_TILTROTOR:
213 case MAV_TYPE_VTOL_FIXEDROTOR:
214 case MAV_TYPE_VTOL_TAILSITTER:
215 case MAV_TYPE_VTOL_TILTWING:
216 case MAV_TYPE_VTOL_RESERVED5:
217 return VehicleClassVTOL;
218 case MAV_TYPE_FIXED_WING:
220 case MAV_TYPE_AIRSHIP:
221 return VehicleClassAirship;
222 default:
223 return VehicleClassGeneric;
224 }
225}
226
228{
229 switch (vehicleClass) {
231 return QCoreApplication::translate("Vehicle Class", "Airship");
233 return QCoreApplication::translate("Vehicle Class", "Fixed Wing");
235 return QCoreApplication::translate("Vehicle Class", "Rover-Boat");
236 case VehicleClassSub:
237 return QCoreApplication::translate("Vehicle Class", "Sub");
239 return QCoreApplication::translate("Vehicle Class", "Spacecraft");
241 return QCoreApplication::translate("Vehicle Class", "Multi-Rotor");
242 case VehicleClassVTOL:
243 return QCoreApplication::translate("Vehicle Class", "VTOL");
245 return QCoreApplication::translate("Vehicle Class", "Generic");
246 default:
247 return QCoreApplication::translate("Vehicle Class", "Unknown");
248 }
249}
250
251MAV_TYPE QGCMAVLink::vehicleTypeFromString(const QString &vehicleStr)
252{
253 const QString type = vehicleStr.trimmed();
254 if (type == QLatin1String("Multi-Rotor")) {
255 return MAV_TYPE_QUADROTOR;
256 }
257 if (type == QLatin1String("Fixed Wing")) {
258 return MAV_TYPE_FIXED_WING;
259 }
260 if (type == QLatin1String("Rover-Boat") || type == QLatin1String("Rover")) {
261 return MAV_TYPE_GROUND_ROVER;
262 }
263 if (type == QLatin1String("Sub")) {
264 return MAV_TYPE_SUBMARINE;
265 }
266 return MAV_TYPE_GENERIC;
267}
268
270{
271 switch (vehicleClass) {
272 case VehicleClassAirship: return "Airship";
273 case VehicleClassFixedWing: return "Fixed Wing";
274 case VehicleClassRoverBoat: return "Rover-Boat";
275 case VehicleClassSub: return "Sub";
276 case VehicleClassSpacecraft:return "Spacecraft";
277 case VehicleClassMultiRotor:return "Multi-Rotor";
278 case VehicleClassVTOL: return "VTOL";
279 case VehicleClassGeneric: return "Generic";
280 default: return "Unknown";
281 }
282}
283
285{
286 switch (vehicleClass) {
288 return QStringLiteral("Airship");
290 return QStringLiteral("FixedWing");
292 return QStringLiteral("RoverBoat");
293 case VehicleClassSub:
294 return QStringLiteral("Sub");
296 return QStringLiteral("Spacecraft");
298 return QStringLiteral("MultiRotor");
299 case VehicleClassVTOL:
300 return QStringLiteral("VTOL");
302 return QStringLiteral("Generic");
303 default:
304 return QStringLiteral("Unknown");
305 }
306}
307
308QString QGCMAVLink::mavResultToString(uint8_t result)
309{
310 switch (result) {
311 case MAV_RESULT_ACCEPTED:
312 return QStringLiteral("MAV_RESULT_ACCEPTED");
313 case MAV_RESULT_TEMPORARILY_REJECTED:
314 return QStringLiteral("MAV_RESULT_TEMPORARILY_REJECTED");
315 case MAV_RESULT_DENIED:
316 return QStringLiteral("MAV_RESULT_DENIED");
317 case MAV_RESULT_UNSUPPORTED:
318 return QStringLiteral("MAV_RESULT_UNSUPPORTED");
319 case MAV_RESULT_FAILED:
320 return QStringLiteral("MAV_RESULT_FAILED");
321 case MAV_RESULT_IN_PROGRESS:
322 return QStringLiteral("MAV_RESULT_IN_PROGRESS");
323 default:
324 return QStringLiteral("MAV_RESULT unknown %1").arg(result);
325 }
326}
327
328QString QGCMAVLink::mavSysStatusSensorToString(MAV_SYS_STATUS_SENSOR sysStatusSensor)
329{
330 struct sensorInfo_s {
331 uint32_t bit;
332 const char* sensorName;
333 };
334
335 static const sensorInfo_s rgSensorInfo[] = {
336 { MAV_SYS_STATUS_SENSOR_3D_GYRO, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Gyro") },
337 { MAV_SYS_STATUS_SENSOR_3D_ACCEL, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Accelerometer") },
338 { MAV_SYS_STATUS_SENSOR_3D_MAG, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Magnetometer") },
339 { MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Absolute pressure") },
340 { MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Differential pressure") },
341 { MAV_SYS_STATUS_SENSOR_GPS, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "GPS") },
342 { MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Optical flow") },
343 { MAV_SYS_STATUS_SENSOR_VISION_POSITION, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Computer vision position") },
344 { MAV_SYS_STATUS_SENSOR_LASER_POSITION, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Laser based position") },
345 { MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "External ground truth") },
346 { MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Angular rate control") },
347 { MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Attitude stabilization") },
348 { MAV_SYS_STATUS_SENSOR_YAW_POSITION, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Yaw position") },
349 { MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Z/altitude control") },
350 { MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "X/Y position control") },
351 { MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Motor outputs / control") },
352 { MAV_SYS_STATUS_SENSOR_RC_RECEIVER, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "RC receiver") },
353 { MAV_SYS_STATUS_SENSOR_3D_GYRO2, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Gyro 2") },
354 { MAV_SYS_STATUS_SENSOR_3D_ACCEL2, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Accelerometer 2") },
355 { MAV_SYS_STATUS_SENSOR_3D_MAG2, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Magnetometer 2") },
356 { MAV_SYS_STATUS_GEOFENCE, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "GeoFence") },
357 { MAV_SYS_STATUS_AHRS, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "AHRS") },
358 { MAV_SYS_STATUS_TERRAIN, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Terrain") },
359 { MAV_SYS_STATUS_REVERSE_MOTOR, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Motors reversed") },
360 { MAV_SYS_STATUS_LOGGING, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Logging") },
361 { MAV_SYS_STATUS_SENSOR_BATTERY, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Battery") },
362 { MAV_SYS_STATUS_SENSOR_PROXIMITY, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Proximity") },
363 { MAV_SYS_STATUS_SENSOR_SATCOM, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Satellite Communication") },
364 { MAV_SYS_STATUS_PREARM_CHECK, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Pre-Arm Check") },
365 { MAV_SYS_STATUS_OBSTACLE_AVOIDANCE, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Avoidance/collision prevention") },
366 { MAV_SYS_STATUS_SENSOR_PROPULSION, QT_TRANSLATE_NOOP("MAVLink SYS_STATUS_SENSOR value", "Propulsion") }
367 };
368
369 for (size_t i=0; i<sizeof(rgSensorInfo)/sizeof(sensorInfo_s); i++) {
370 const sensorInfo_s* pSensorInfo = &rgSensorInfo[i];
371 if (sysStatusSensor == pSensorInfo->bit) {
372 return QCoreApplication::translate("MAVLink SYS_STATUS_SENSOR value", pSensorInfo->sensorName);
373 }
374 }
375
376 qWarning() << "QGCMAVLink::mavSysStatusSensorToString: Unknown sensor" << sysStatusSensor;
377
378 return QCoreApplication::translate("MAVLink unknown SYS_STATUS_SENSOR value", "Unknown sensor");
379}
380
381QString QGCMAVLink::mavTypeToString(MAV_TYPE mavType) {
382 switch (mavType) {
383 case MAV_TYPE_GENERIC: return QCoreApplication::translate("MAV_TYPE", "Generic micro air vehicle");
384 case MAV_TYPE_FIXED_WING: return QCoreApplication::translate("MAV_TYPE", "Fixed wing aircraft");
385 case MAV_TYPE_QUADROTOR: return QCoreApplication::translate("MAV_TYPE", "Quadrotor");
386 case MAV_TYPE_COAXIAL: return QCoreApplication::translate("MAV_TYPE", "Coaxial helicopter");
387 case MAV_TYPE_HELICOPTER: return QCoreApplication::translate("MAV_TYPE", "Normal helicopter with tail rotor.");
388 case MAV_TYPE_ANTENNA_TRACKER: return QCoreApplication::translate("MAV_TYPE", "Ground installation");
389 case MAV_TYPE_GCS: return QCoreApplication::translate("MAV_TYPE", "Operator control unit / ground control station");
390 case MAV_TYPE_AIRSHIP: return QCoreApplication::translate("MAV_TYPE", "Airship, controlled");
391 case MAV_TYPE_FREE_BALLOON: return QCoreApplication::translate("MAV_TYPE", "Free balloon, uncontrolled");
392 case MAV_TYPE_ROCKET: return QCoreApplication::translate("MAV_TYPE", "Rocket");
393 case MAV_TYPE_GROUND_ROVER: return QCoreApplication::translate("MAV_TYPE", "Ground rover");
394 case MAV_TYPE_SURFACE_BOAT: return QCoreApplication::translate("MAV_TYPE", "Surface vessel, boat, ship");
395 case MAV_TYPE_SUBMARINE: return QCoreApplication::translate("MAV_TYPE", "Submarine");
396 case MAV_TYPE_SPACECRAFT_ORBITER: return QCoreApplication::translate("MAV_TYPE", "Spacecraft, orbiter");
397 case MAV_TYPE_HEXAROTOR: return QCoreApplication::translate("MAV_TYPE", "Hexarotor");
398 case MAV_TYPE_OCTOROTOR: return QCoreApplication::translate("MAV_TYPE", "Octorotor");
399 case MAV_TYPE_TRICOPTER: return QCoreApplication::translate("MAV_TYPE", "trirotor");
400 case MAV_TYPE_FLAPPING_WING: return QCoreApplication::translate("MAV_TYPE", "Flapping wing");
401 case MAV_TYPE_KITE: return QCoreApplication::translate("MAV_TYPE", "Kite");
402 case MAV_TYPE_ONBOARD_CONTROLLER: return QCoreApplication::translate("MAV_TYPE", "Onboard companion controller");
403 case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: return QCoreApplication::translate("MAV_TYPE", "Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter");
404 case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: return QCoreApplication::translate("MAV_TYPE", "Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter");
405 case MAV_TYPE_VTOL_TILTROTOR: return QCoreApplication::translate("MAV_TYPE", "Tiltrotor VTOL");
406 case MAV_TYPE_VTOL_FIXEDROTOR: return QCoreApplication::translate("MAV_TYPE", "VTOL Fixedrotor");
407 case MAV_TYPE_VTOL_TAILSITTER: return QCoreApplication::translate("MAV_TYPE", "VTOL Tailsitter");
408 case MAV_TYPE_VTOL_TILTWING: return QCoreApplication::translate("MAV_TYPE", "VTOL Tiltwing");
409 case MAV_TYPE_VTOL_RESERVED5: return QCoreApplication::translate("MAV_TYPE", "VTOL reserved 5");
410 case MAV_TYPE_GIMBAL: return QCoreApplication::translate("MAV_TYPE", "Onboard gimbal");
411 case MAV_TYPE_ADSB: return QCoreApplication::translate("MAV_TYPE", "Onboard ADSB peripheral");
412 default: return QStringLiteral("MAV_TYPE_UNKNOWN");
413 }
414}
415
416QString QGCMAVLink::firmwareVersionTypeToString(FIRMWARE_VERSION_TYPE firmwareVersionType)
417{
418 switch (firmwareVersionType) {
419 case FIRMWARE_VERSION_TYPE_DEV:
420 return QStringLiteral("dev");
421 case FIRMWARE_VERSION_TYPE_ALPHA:
422 return QStringLiteral("alpha");
423 case FIRMWARE_VERSION_TYPE_BETA:
424 return QStringLiteral("beta");
425 case FIRMWARE_VERSION_TYPE_RC:
426 return QStringLiteral("rc");
427 case FIRMWARE_VERSION_TYPE_OFFICIAL:
428 default:
429 return QStringLiteral("");
430 }
431}
432
433FIRMWARE_VERSION_TYPE QGCMAVLink::firmwareVersionTypeFromString(const QString &typeStr)
434{
435 const QString type = typeStr.trimmed();
436 if (type == QLatin1String("dev")) {
437 return FIRMWARE_VERSION_TYPE_DEV;
438 }
439 if (type == QLatin1String("alpha")) {
440 return FIRMWARE_VERSION_TYPE_ALPHA;
441 }
442 if (type == QLatin1String("beta")) {
443 return FIRMWARE_VERSION_TYPE_BETA;
444 }
445 if (type == QLatin1String("rc")) {
446 return FIRMWARE_VERSION_TYPE_RC;
447 }
448 return FIRMWARE_VERSION_TYPE_OFFICIAL;
449}
450
451int QGCMAVLink::motorCount(MAV_TYPE mavType, uint8_t frameType)
452{
453 switch (mavType) {
454 case MAV_TYPE_HELICOPTER:
455 return 1;
456 case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR:
457 return 2;
458 case MAV_TYPE_TRICOPTER:
459 return 3;
460 case MAV_TYPE_QUADROTOR:
461 case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR:
462 return 4;
463 case MAV_TYPE_HEXAROTOR:
464 return 6;
465 case MAV_TYPE_OCTOROTOR:
466 return 8;
467 case MAV_TYPE_SUBMARINE:
468 {
469 // Supported frame types
470 enum {
471 SUB_FRAME_BLUEROV1,
472 SUB_FRAME_VECTORED,
473 SUB_FRAME_VECTORED_6DOF,
474 SUB_FRAME_VECTORED_6DOF_90DEG,
475 SUB_FRAME_SIMPLEROV_3,
476 SUB_FRAME_SIMPLEROV_4,
477 SUB_FRAME_SIMPLEROV_5,
478 SUB_FRAME_CUSTOM
479 };
480
481 switch (frameType) { // ardupilot/libraries/AP_Motors/AP_Motors6DOF.h sub_frame_t
482
483 case SUB_FRAME_BLUEROV1:
484 case SUB_FRAME_VECTORED:
485 return 6;
486
487 case SUB_FRAME_SIMPLEROV_3:
488 return 3;
489
490 case SUB_FRAME_SIMPLEROV_4:
491 return 4;
492
493 case SUB_FRAME_SIMPLEROV_5:
494 return 5;
495
496 case SUB_FRAME_VECTORED_6DOF:
497 case SUB_FRAME_VECTORED_6DOF_90DEG:
498 case SUB_FRAME_CUSTOM:
499 return 8;
500
501 default:
502 return -1;
503 }
504 }
505 case MAV_TYPE_SPACECRAFT_ORBITER:
506 return 8;
507
508 default:
509 return -1;
510 }
511}
512
514{
515 struct failure2Sensor_s {
516 HL_FAILURE_FLAG failureBit;
517 MAV_SYS_STATUS_SENSOR sensorBit;
518 };
519
520 static constexpr const failure2Sensor_s rgFailure2Sensor[] = {
521 { HL_FAILURE_FLAG_GPS, MAV_SYS_STATUS_SENSOR_GPS },
522 { HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE },
523 { HL_FAILURE_FLAG_ABSOLUTE_PRESSURE, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE },
524 { HL_FAILURE_FLAG_3D_ACCEL, MAV_SYS_STATUS_SENSOR_3D_ACCEL },
525 { HL_FAILURE_FLAG_3D_GYRO, MAV_SYS_STATUS_SENSOR_3D_GYRO },
526 { HL_FAILURE_FLAG_3D_MAG, MAV_SYS_STATUS_SENSOR_3D_MAG },
527 };
528
529 // Map from MAV_FAILURE bits to standard SYS_STATUS message handling
530 uint32_t onboardControlSensorsEnabled = 0;
531 for (size_t i=0; i<sizeof(rgFailure2Sensor)/sizeof(failure2Sensor_s); i++) {
532 const failure2Sensor_s* pFailure2Sensor = &rgFailure2Sensor[i];
533 if (highLatency2.failure_flags & pFailure2Sensor->failureBit) {
534 // Assume if reporting as unhealthy that is it present and enabled
535 onboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
536 }
537 }
538
539 return onboardControlSensorsEnabled;
540}
541
542QString QGCMAVLink::compIdToString(uint8_t compId)
543{
544 QString compIdStr;
545
546 if (mavlinkCompIdHash.contains(compId)) {
547 compIdStr = mavlinkCompIdHash.value(compId);
548 } else {
549 compIdStr = QStringLiteral("Unknown");
550 }
551
552 return QStringLiteral("%1 (%2)").arg(compIdStr).arg(static_cast<int>(compId));
553}
#define MAVLINK_COMM_NUM_BUFFERS
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_high_latency2_t mavlink_high_latency2_t
static constexpr VehicleClass_t VehicleClassGeneric