GCS_MAVLink: sensor flags, only mark AHRS as enabled once initialised

This commit is contained in:
Peter Hall 2021-02-13 00:26:15 +00:00 committed by Andrew Tridgell
parent 2302f08f75
commit c1a831bbf4

View File

@ -136,10 +136,12 @@ void GCS::update_sensor_status_flags()
const AP_InertialSensor &ins = AP::ins();
control_sensors_present |= MAV_SYS_STATUS_AHRS;
control_sensors_enabled |= MAV_SYS_STATUS_AHRS;
if (!ahrs.initialised() || ahrs.healthy()) {
if (!ahrs.have_inertial_nav() || ins.accel_calibrated_ok_all()) {
control_sensors_health |= MAV_SYS_STATUS_AHRS;
if (ahrs.initialised()) {
control_sensors_enabled |= MAV_SYS_STATUS_AHRS;
if (ahrs.healthy()) {
if (!ahrs.have_inertial_nav() || ins.accel_calibrated_ok_all()) {
control_sensors_health |= MAV_SYS_STATUS_AHRS;
}
}
}