Browse Source

Rover: only report ahrs unhealthy after initialisation

master
Randy Mackay 11 years ago
parent
commit
799f559c1d
  1. 2
      APMrover2/GCS_Mavlink.pde

2
APMrover2/GCS_Mavlink.pde

@ -169,7 +169,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -169,7 +169,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
control_sensors_health &= ~MAV_SYS_STATUS_SENSOR_3D_ACCEL;
}
if (!ahrs.healthy()) {
if (ahrs.initialised() && !ahrs.healthy()) {
// AHRS subsystem is unhealthy
control_sensors_health &= ~MAV_SYS_STATUS_AHRS;
}

Loading…
Cancel
Save