Copter: individual accel and gyro status to GCS

This commit is contained in:
Randy Mackay 2014-09-01 20:22:18 +09:00
parent d7343d5dc7
commit 4a06941a39
1 changed files with 5 additions and 2 deletions

View File

@ -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()) {