mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_GPS: fixed handling of driver destruction
this allows for more complex destructors, and ensures we don't have multiple backends allocated at once per instance
This commit is contained in:
parent
7ceba8dce4
commit
9781175bf5
@ -182,9 +182,6 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
|
||||
if (new_gps != NULL) {
|
||||
state[instance].status = NO_FIX;
|
||||
if (drivers[instance] != NULL) {
|
||||
delete drivers[instance];
|
||||
}
|
||||
drivers[instance] = new_gps;
|
||||
timing[instance].last_message_time_ms = now;
|
||||
}
|
||||
@ -222,6 +219,10 @@ AP_GPS::update_instance(uint8_t instance)
|
||||
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;
|
||||
}
|
||||
} else {
|
||||
timing[instance].last_message_time_ms = tnow;
|
||||
|
@ -25,6 +25,10 @@ class AP_GPS_Backend
|
||||
public:
|
||||
AP_GPS_Backend(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
||||
|
||||
// we declare a virtual destructor so that GPS drivers can
|
||||
// override with a custom destructor if need be.
|
||||
virtual ~AP_GPS_Backend(void) {}
|
||||
|
||||
// The read() method is the only one needed in each driver. It
|
||||
// should return true when the backend has successfully received a
|
||||
// valid packet from the GPS.
|
||||
|
Loading…
Reference in New Issue
Block a user