mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: report baro health to GCS
This commit is contained in:
parent
caeb2c4d0d
commit
1e374ab42b
@ -182,8 +182,14 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
// default to all healthy except compass, gps and receiver which we set individually
|
// default to all healthy except baro, compass, gps and receiver which we set individually
|
||||||
control_sensors_health = control_sensors_present & (~MAV_SYS_STATUS_SENSOR_3D_MAG & ~MAV_SYS_STATUS_SENSOR_GPS & ~MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
|
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE |
|
||||||
|
MAV_SYS_STATUS_SENSOR_3D_MAG |
|
||||||
|
MAV_SYS_STATUS_SENSOR_GPS |
|
||||||
|
MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
|
||||||
|
if (barometer.healthy) {
|
||||||
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
|
||||||
|
}
|
||||||
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
|
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user