From 2dbe15911f61e726fbb2d9768023147aadbb0b10 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 23 Oct 2021 09:03:28 +1100 Subject: [PATCH] AP_GPS: change empty constructors out for 'use AP_GPS_Backend::AP_GPS_Backend' --- libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp | 5 ----- libraries/AP_GPS/AP_GPS_ExternalAHRS.h | 3 ++- libraries/AP_GPS/AP_GPS_MAV.cpp | 5 ----- libraries/AP_GPS/AP_GPS_MAV.h | 3 ++- libraries/AP_GPS/AP_GPS_MSP.cpp | 5 ----- libraries/AP_GPS/AP_GPS_MSP.h | 3 ++- 6 files changed, 6 insertions(+), 18 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp b/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp index bd9c910c79..76a3bf7e89 100644 --- a/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp +++ b/libraries/AP_GPS/AP_GPS_ExternalAHRS.cpp @@ -21,11 +21,6 @@ #if HAL_EXTERNAL_AHRS_ENABLED -AP_GPS_ExternalAHRS::AP_GPS_ExternalAHRS(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port) -{ -} - // Reading does nothing in this class; we simply return whether or not // the latest reading has been consumed. By calling this function we assume // the caller is consuming the new data; diff --git a/libraries/AP_GPS/AP_GPS_ExternalAHRS.h b/libraries/AP_GPS/AP_GPS_ExternalAHRS.h index 52352a726d..4acd4b4282 100644 --- a/libraries/AP_GPS/AP_GPS_ExternalAHRS.h +++ b/libraries/AP_GPS/AP_GPS_ExternalAHRS.h @@ -29,7 +29,8 @@ class AP_GPS_ExternalAHRS : public AP_GPS_Backend { public: - AP_GPS_ExternalAHRS(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); + + using AP_GPS_Backend::AP_GPS_Backend; bool read() override; void handle_external(const AP_ExternalAHRS::gps_data_message_t &pkt) override; diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 62cc13da76..0f4cdf715d 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -19,11 +19,6 @@ #include "AP_GPS_MAV.h" #include -AP_GPS_MAV::AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port) -{ -} - // Reading does nothing in this class; we simply return whether or not // the latest reading has been consumed. By calling this function we assume // the caller is consuming the new data; diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index 642a47889a..7566e5f22a 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -27,7 +27,8 @@ class AP_GPS_MAV : public AP_GPS_Backend { public: - AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); + + using AP_GPS_Backend::AP_GPS_Backend; bool read() override; diff --git a/libraries/AP_GPS/AP_GPS_MSP.cpp b/libraries/AP_GPS/AP_GPS_MSP.cpp index c3a807fc0c..1229f3a0d8 100644 --- a/libraries/AP_GPS/AP_GPS_MSP.cpp +++ b/libraries/AP_GPS/AP_GPS_MSP.cpp @@ -21,11 +21,6 @@ #if HAL_MSP_GPS_ENABLED -AP_GPS_MSP::AP_GPS_MSP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : - AP_GPS_Backend(_gps, _state, _port) -{ -} - // Reading does nothing in this class; we simply return whether or not // the latest reading has been consumed. By calling this function we assume // the caller is consuming the new data; diff --git a/libraries/AP_GPS/AP_GPS_MSP.h b/libraries/AP_GPS/AP_GPS_MSP.h index aaf3db6eec..140c2e9748 100644 --- a/libraries/AP_GPS/AP_GPS_MSP.h +++ b/libraries/AP_GPS/AP_GPS_MSP.h @@ -29,7 +29,8 @@ class AP_GPS_MSP : public AP_GPS_Backend { public: - AP_GPS_MSP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); + + using AP_GPS_Backend::AP_GPS_Backend; bool read() override; void handle_msp(const MSP::msp_gps_data_message_t &pkt) override;