AP_GPS: Only setup state's instance field during init
This commit is contained in:
parent
52ddaa3e72
commit
5684a5dd36
@ -281,6 +281,11 @@ void AP_GPS::init(const AP_SerialManager& serial_manager)
|
||||
// Initialise class variables used to do GPS blending
|
||||
_omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f);
|
||||
|
||||
// prep the state instance fields
|
||||
for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) {
|
||||
state[i].instance = i;
|
||||
}
|
||||
|
||||
// sanity check update rate
|
||||
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
||||
if (_rate_ms[i] <= 0 || _rate_ms[i] > GPS_MAX_RATE_MS) {
|
||||
@ -399,7 +404,6 @@ 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;
|
||||
@ -618,7 +622,6 @@ void AP_GPS::update_instance(uint8_t instance)
|
||||
delete drivers[instance];
|
||||
drivers[instance] = nullptr;
|
||||
memset(&state[instance], 0, sizeof(state[instance]));
|
||||
state[instance].instance = instance;
|
||||
state[instance].status = NO_GPS;
|
||||
state[instance].hdop = GPS_UNKNOWN_DOP;
|
||||
state[instance].vdop = GPS_UNKNOWN_DOP;
|
||||
|
Loading…
Reference in New Issue
Block a user