|
|
|
@ -3584,36 +3584,40 @@ QStringList Vehicle::unhealthySensors() const
@@ -3584,36 +3584,40 @@ QStringList Vehicle::unhealthySensors() const
|
|
|
|
|
|
|
|
|
|
struct sensorInfo_s { |
|
|
|
|
uint32_t bit; |
|
|
|
|
const char* sensorName; |
|
|
|
|
QString sensorName; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
static const sensorInfo_s rgSensorInfo[] = { |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_GYRO, "Gyro" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL, "Accelerometer" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_MAG, "Magnetometer" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, "Absolute pressure" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, "Differential pressure" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_GPS, "GPS" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, "Optical flow" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_VISION_POSITION, "Computer vision position" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_LASER_POSITION, "Laser based position" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, "External ground truth" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, "Angular rate control" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, "Attitude stabilization" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_YAW_POSITION, "Yaw position" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, "Z/altitude control" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, "X/Y position control" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, "Motor outputs / control" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_RC_RECEIVER, "RC receiver" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_GYRO2, "Gyro 2" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL2, "Accelerometer 2" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_MAG2, "Magnetometer 2" }, |
|
|
|
|
{ MAV_SYS_STATUS_GEOFENCE, "GeoFence" }, |
|
|
|
|
{ MAV_SYS_STATUS_AHRS, "AHRS" }, |
|
|
|
|
{ MAV_SYS_STATUS_TERRAIN, "Terrain" }, |
|
|
|
|
{ MAV_SYS_STATUS_REVERSE_MOTOR, "Motors reversed" }, |
|
|
|
|
{ MAV_SYS_STATUS_LOGGING, "Logging" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_BATTERY, "Battery" }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_GYRO, tr("Gyro") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL, tr("Accelerometer") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_MAG, tr("Magnetometer") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, tr("Absolute pressure") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, tr("Differential pressure") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_GPS, tr("GPS") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, tr("Optical flow") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_VISION_POSITION, tr("Computer vision position") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_LASER_POSITION, tr("Laser based position") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH, tr("External ground truth") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL, tr("Angular rate control") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, tr("Attitude stabilization") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_YAW_POSITION, tr("Yaw position") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL, tr("Z/altitude control") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL, tr("X/Y position control") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS, tr("Motor outputs / control") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_RC_RECEIVER, tr("RC receiver") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_GYRO2, tr("Gyro 2") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_ACCEL2, tr("Accelerometer 2") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_3D_MAG2, tr("Magnetometer 2") }, |
|
|
|
|
{ MAV_SYS_STATUS_GEOFENCE, tr("GeoFence") }, |
|
|
|
|
{ MAV_SYS_STATUS_AHRS, tr("AHRS") }, |
|
|
|
|
{ MAV_SYS_STATUS_TERRAIN, tr("Terrain") }, |
|
|
|
|
{ MAV_SYS_STATUS_REVERSE_MOTOR, tr("Motors reversed") }, |
|
|
|
|
{ MAV_SYS_STATUS_LOGGING, tr("Logging") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_BATTERY, tr("Battery") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_PROXIMITY, tr("Proximity") }, |
|
|
|
|
{ MAV_SYS_STATUS_SENSOR_SATCOM, tr("Satellite Communication") }, |
|
|
|
|
{ MAV_SYS_STATUS_PREARM_CHECK, tr("Pre-Arm Check") }, |
|
|
|
|
{ MAV_SYS_STATUS_OBSTACLE_AVOIDANCE, tr("Avoidance/collision prevention") }, |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
for (size_t i=0; i<sizeof(rgSensorInfo)/sizeof(sensorInfo_s); i++) { |
|
|
|
|