mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Rover: GPS reported healthy to GCS even without lock
a GPS is unhealthy when it cannot be contacted. Not having a 3D lock should not make the GPS unhealthy.
This commit is contained in:
parent
bce9a40ab5
commit
a8da459baf
@ -329,7 +329,7 @@ void Rover::update_sensor_status_flags(void)
|
||||
if (g.compass_enabled && compass.healthy(0) && ahrs.use_compass()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||
}
|
||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.is_healthy()) {
|
||||
if (gps.is_healthy()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||
}
|
||||
if (g2.visual_odom.enabled() && !g2.visual_odom.healthy()) {
|
||||
|
Loading…
Reference in New Issue
Block a user