mirror of https://github.com/ArduPilot/ardupilot
Copter: individual accel and gyro status to GCS
This commit is contained in:
parent
d7343d5dc7
commit
4a06941a39
|
@ -199,8 +199,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
|
|||
if (ap.rc_receiver_present && !failsafe.radio) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
|
||||
}
|
||||
if (!ins.healthy()) {
|
||||
control_sensors_health &= ~(MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL);
|
||||
if (!ins.get_gyro_health_all()) {
|
||||
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 (!ahrs.healthy()) {
|
||||
|
|
Loading…
Reference in New Issue