mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Plane: individual accel and gyro status to GCS
This commit is contained in:
parent
4a06941a39
commit
c2cdc0468b
@ -225,8 +225,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
|||||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||||
}
|
}
|
||||||
if (!ins.healthy()) {
|
if (!ins.get_gyro_health_all()) {
|
||||||
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_GYRO;
|
||||||
|
}
|
||||||
|
if (!ins.get_accel_health_all()) {
|
||||||
|
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
|
||||||
}
|
}
|
||||||
if (airspeed.healthy()) {
|
if (airspeed.healthy()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
|
||||||
|
Loading…
Reference in New Issue
Block a user