Browse Source

Plane: use baro healthy()

Use baro last update time in place of healthy to determine whether HIL
sensor updates have started
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
7d7272520e
  1. 2
      ArduPlane/GCS_Mavlink.pde
  2. 4
      ArduPlane/system.pde
  3. 2
      ArduPlane/test.pde

2
ArduPlane/GCS_Mavlink.pde

@ -216,7 +216,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -216,7 +216,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}
if (barometer.healthy) {
if (barometer.healthy()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
}
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {

4
ArduPlane/system.pde

@ -456,8 +456,8 @@ static void check_short_failsafe() @@ -456,8 +456,8 @@ static void check_short_failsafe()
static void startup_INS_ground(bool do_accel_init)
{
#if HIL_MODE != HIL_MODE_DISABLED
while (!barometer.healthy) {
// the barometer becomes healthy when we get the first
while (barometer.get_last_update() == 0) {
// the barometer begins updating when we get the first
// HIL_STATE message
gcs_send_text_P(SEVERITY_LOW, PSTR("Waiting for first HIL_STATE message"));
delay(1000);

2
ArduPlane/test.pde

@ -578,7 +578,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv) @@ -578,7 +578,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
while(1) {
delay(100);
if (!barometer.healthy) {
if (!barometer.healthy()) {
cliSerial->println_P(PSTR("not healthy"));
} else {
cliSerial->printf_P(PSTR("Alt: %0.2fm, Raw: %f Temperature: %.1f\n"),

Loading…
Cancel
Save