mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Rover: consider GPS unhealthy if it doesn't have GPS lock
This commit is contained in:
parent
369c130c2d
commit
7aef90a1f3
@ -158,7 +158,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||||||
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
|
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
|
||||||
}
|
}
|
||||||
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS) {
|
if (g_gps != NULL && g_gps->status() >= GPS::GPS_OK_FIX_3D) {
|
||||||
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
|
||||||
}
|
}
|
||||||
if (!ins.healthy()) {
|
if (!ins.healthy()) {
|
||||||
|
Loading…
Reference in New Issue
Block a user