mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_GPS: zero state structure on driver release
this ensures no values are left from the previous driver
This commit is contained in:
parent
2ddc414f4d
commit
79f5618f6f
@ -221,12 +221,14 @@ AP_GPS::update_instance(uint8_t instance)
|
||||
// detection to run again
|
||||
if (!result) {
|
||||
if (tnow - timing[instance].last_message_time_ms > 1200) {
|
||||
state[instance].status = NO_GPS;
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
// free the driver before we run the next detection, so we
|
||||
// don't end up with two allocated at any time
|
||||
delete drivers[instance];
|
||||
drivers[instance] = NULL;
|
||||
memset(&state[instance], 0, sizeof(state[instance]));
|
||||
state[instance].instance = instance;
|
||||
state[instance].status = NO_GPS;
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
}
|
||||
} else {
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
|
Loading…
Reference in New Issue
Block a user