diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index 979bda5072..a1be658010 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -32,12 +32,6 @@ extern const AP_HAL::HAL& hal; # define Debug(fmt, args ...) #endif -AP_GPS_ERB::AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - next_fix(AP_GPS::NO_FIX) -{ -} - // Process bytes available from the stream // // The stream is assumed to contain only messages we recognise. If it diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index 8eacac6729..69fde51d69 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -27,7 +27,8 @@ class AP_GPS_ERB : public AP_GPS_Backend { public: - AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); + + using AP_GPS_Backend::AP_GPS_Backend; // Methods bool read() override; @@ -150,5 +151,5 @@ private: bool _parse_gps(); // used to update fix between status and position packets - AP_GPS::GPS_Status next_fix; + AP_GPS::GPS_Status next_fix = AP_GPS::NO_FIX; }; diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 10b9557204..ae55765867 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -28,9 +28,7 @@ const char AP_GPS_MTK::_initialisation_blob[] = MTK_OUTPUT_5HZ SBAS_ON WAAS_ON MTK_NAVTHRES_OFF; AP_GPS_MTK::AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port), - _step(0), - _payload_counter(0) + AP_GPS_Backend(_gps, _state, _port) { gps.send_blob_start(state.instance, _initialisation_blob, sizeof(_initialisation_blob)); } diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index a24c2b70c2..1ec6120f1d 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -50,13 +50,6 @@ extern const AP_HAL::HAL& hal; #define DIGIT_TO_VAL(_x) (_x - '0') #define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x)) -AP_GPS_NMEA::AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port) -{ - // this guarantees that _term is always null terminated - memset(_term, 0, sizeof(_term)); -} - bool AP_GPS_NMEA::read(void) { int16_t numc; diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 31c35e207e..a7f982902e 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -53,7 +53,8 @@ class AP_GPS_NMEA : public AP_GPS_Backend friend class AP_GPS_NMEA_Test; public: - AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); + + using AP_GPS_Backend::AP_GPS_Backend; /// Checks the serial receive buffer for characters, /// attempts to parse NMEA data and updates internal state