Skip to content

Commit

Permalink
AP_GPS: fixed UAVCAN as 2nd GPS
Browse files Browse the repository at this point in the history
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
  • Loading branch information
tridge authored and OXINARF committed Jul 18, 2017
1 parent d2c5786 commit 82e7e44
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 82e7e44

Please sign in to comment.