Browse Source

AP_GPS: fixed UAVCAN as 2nd GPS

This fixes the issue here:

  https://discuss.ardupilot.org/t/ac3-6-dev-dual-gps-issues/19172

thanks to Francisco for spotting the issue

this is tested with UAVCAN as 2nd GPS, ublox as primary
mission-4.1.18
Andrew Tridgell 8 years ago committed by Francisco Ferreira
parent
commit
82e7e44cc3
  1. 10
      libraries/AP_GPS/AP_GPS.cpp

10
libraries/AP_GPS/AP_GPS.cpp

@ -399,6 +399,11 @@ void AP_GPS::detect_instance(uint8_t instance) @@ -399,6 +399,11 @@ void AP_GPS::detect_instance(uint8_t instance)
struct detect_state *dstate = &detect_state[instance];
uint32_t now = AP_HAL::millis();
state[instance].instance = instance;
state[instance].status = NO_GPS;
state[instance].hdop = GPS_UNKNOWN_DOP;
state[instance].vdop = GPS_UNKNOWN_DOP;
switch (_type[instance]) {
#if CONFIG_HAL_BOARD == HAL_BOARD_QURT
case GPS_TYPE_QURT:
@ -456,11 +461,6 @@ void AP_GPS::detect_instance(uint8_t instance) @@ -456,11 +461,6 @@ void AP_GPS::detect_instance(uint8_t instance)
return;
}
state[instance].instance = instance;
state[instance].status = NO_GPS;
state[instance].hdop = GPS_UNKNOWN_DOP;
state[instance].vdop = GPS_UNKNOWN_DOP;
// all remaining drivers automatically cycle through baud rates to detect
// the correct baud rate, and should have the selected baud broadcast
dstate->auto_detected_baud = true;

Loading…
Cancel
Save