GCS_MAVLink: sensor flags, only mark AHRS as enabled once initialised
This commit is contained in:
parent
2302f08f75
commit
c1a831bbf4
@ -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;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user