330 struct sensorInfo_s {
332 const char* sensorName;
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") }
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);
376 qWarning() <<
"QGCMAVLink::mavSysStatusSensorToString: Unknown sensor" << sysStatusSensor;
378 return QCoreApplication::translate(
"MAVLink unknown SYS_STATUS_SENSOR value",
"Unknown sensor");
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");
515 struct failure2Sensor_s {
516 HL_FAILURE_FLAG failureBit;
517 MAV_SYS_STATUS_SENSOR sensorBit;
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 },
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) {
535 onboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
539 return onboardControlSensorsEnabled;