Browse Source

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
c415-sdk
Andrew Tridgell 4 years ago committed by Randy Mackay
parent
commit
45daff9f47
  1. 2
      libraries/GCS_MAVLink/GCS.cpp

2
libraries/GCS_MAVLink/GCS.cpp

@ -150,7 +150,7 @@ void GCS::update_sensor_status_flags() @@ -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…
Cancel
Save