Browse Source

Plane: report baro health to GCS

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
b619c3956c
  1. 9
      ArduPlane/GCS_Mavlink.pde

9
ArduPlane/GCS_Mavlink.pde

@ -205,8 +205,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -205,8 +205,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
break;
}
// default: all present sensors healthy except 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
control_sensors_health = control_sensors_present & ~(MAV_SYS_STATUS_SENSOR_3D_MAG |
// default: all present sensors healthy except baro, 3D_MAG, GPS, DIFFERNTIAL_PRESSURE. GEOFENCE always defaults to healthy.
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_DIFFERENTIAL_PRESSURE);
control_sensors_health |= MAV_SYS_STATUS_GEOFENCE;
@ -215,7 +216,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -215,7 +216,9 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
if (barometer.healthy) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}

Loading…
Cancel
Save