mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: redetection not necessary for UAVCAN GPS
This commit is contained in:
parent
664b181d16
commit
d122f00c14
@ -717,8 +717,8 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
state[instance].vdop = GPS_UNKNOWN_DOP;
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
timing[instance].delta_time_ms = GPS_TIMEOUT_MS;
|
||||
// do not try to detect again if type is MAV
|
||||
if (_type[instance] == GPS_TYPE_MAV) {
|
||||
// do not try to detect again if type is MAV or UAVCAN
|
||||
if (_type[instance] == GPS_TYPE_MAV || _type[instance] == GPS_TYPE_UAVCAN) {
|
||||
state[instance].status = NO_FIX;
|
||||
} else {
|
||||
// free the driver before we run the next detection, so we
|
||||
|
Loading…
Reference in New Issue
Block a user