mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
GCS_MAVLINK: mag health reported in SYS_STATUS should not depend on AHRS use
When using external yaw, EKF3 always reports use_compass as false, which causes the GCS to get a bad compass health message. thanks to Argosdyne for reporting
This commit is contained in:
parent
f8a59a4a72
commit
45daff9f47
@ -150,7 +150,7 @@ void GCS::update_sensor_status_flags()
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (compass.enabled() && compass.healthy() && ahrs.use_compass()) {
|
||||
if (compass.enabled() && compass.healthy()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user