From fd888727b8fff03b15d2e49d46321fde3342ac69 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Nov 2018 21:58:08 +1100 Subject: [PATCH] AP_GPS: add override keyword where required --- libraries/AP_GPS/AP_GPS_ERB.h | 6 +++--- libraries/AP_GPS/AP_GPS_GSOF.h | 4 ++-- libraries/AP_GPS/AP_GPS_MAV.h | 4 ++-- libraries/AP_GPS/AP_GPS_MTK.h | 2 +- libraries/AP_GPS/AP_GPS_MTK19.h | 2 +- libraries/AP_GPS/AP_GPS_NMEA.h | 2 +- libraries/AP_GPS/AP_GPS_NOVA.h | 4 ++-- libraries/AP_GPS/AP_GPS_SBF.h | 4 ++-- libraries/AP_GPS/AP_GPS_SBP.h | 6 +++--- libraries/AP_GPS/AP_GPS_SIRF.h | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.h | 6 +++--- 11 files changed, 21 insertions(+), 21 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index e025d186ab..8eacac6729 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -30,11 +30,11 @@ public: AP_GPS_ERB(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); // Methods - bool read(); + bool read() override; - AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } - bool supports_mavlink_gps_rtk_message() { return true; } + bool supports_mavlink_gps_rtk_message() override { return true; } static bool _detect(struct ERB_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index 374c77f427..be62ab69ac 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -27,12 +27,12 @@ class AP_GPS_GSOF : public AP_GPS_Backend public: AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - AP_GPS::GPS_Status highest_supported_status(void) { + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } // Methods - bool read(); + bool read() override; const char *name() const override { return "GSOF"; } diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index 541af76c78..8ea8d6ad0f 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -29,11 +29,11 @@ class AP_GPS_MAV : public AP_GPS_Backend { public: AP_GPS_MAV(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - bool read(); + bool read() override; static bool _detect(struct MAV_detect_state &state, uint8_t data); - void handle_msg(const mavlink_message_t *msg); + void handle_msg(const mavlink_message_t *msg) override; const char *name() const override { return "MAV"; } diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 21c2523c5e..2de8d2ed89 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -31,7 +31,7 @@ class AP_GPS_MTK : public AP_GPS_Backend { public: AP_GPS_MTK(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - bool read(void); + bool read(void) override; static bool _detect(struct MTK_detect_state &state, uint8_t data); static void send_init_blob(uint8_t instance, AP_GPS &gps); diff --git a/libraries/AP_GPS/AP_GPS_MTK19.h b/libraries/AP_GPS/AP_GPS_MTK19.h index 7933b8311a..21a1371452 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.h +++ b/libraries/AP_GPS/AP_GPS_MTK19.h @@ -32,7 +32,7 @@ class AP_GPS_MTK19 : public AP_GPS_Backend { public: AP_GPS_MTK19(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - bool read(void); + bool read(void) override; static bool _detect(struct MTK19_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index d358b12f9c..712410efb9 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -58,7 +58,7 @@ public: /// Checks the serial receive buffer for characters, /// attempts to parse NMEA data and updates internal state /// accordingly. - bool read(); + bool read() override; static bool _detect(struct NMEA_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_NOVA.h b/libraries/AP_GPS/AP_GPS_NOVA.h index 2be286c942..4c0212508a 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.h +++ b/libraries/AP_GPS/AP_GPS_NOVA.h @@ -27,10 +27,10 @@ class AP_GPS_NOVA : public AP_GPS_Backend public: AP_GPS_NOVA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } // Methods - bool read(); + bool read() override; void inject_data(const uint8_t *data, uint16_t len) override; diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index fa0ad42524..3acff8b525 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -32,10 +32,10 @@ class AP_GPS_SBF : public AP_GPS_Backend public: AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } // Methods - bool read(); + bool read() override; const char *name() const override { return "SBF"; } diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index be48c481a9..1de5c9f9e5 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -29,12 +29,12 @@ class AP_GPS_SBP : public AP_GPS_Backend public: AP_GPS_SBP(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } - bool supports_mavlink_gps_rtk_message() { return true; } + bool supports_mavlink_gps_rtk_message() override { return true; } // Methods - bool read(); + bool read() override; void inject_data(const uint8_t *data, uint16_t len) override; diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index 962c657b40..297f2025d0 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -31,7 +31,7 @@ class AP_GPS_SIRF : public AP_GPS_Backend { public: AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); - bool read(); + bool read() override; static bool _detect(struct SIRF_detect_state &state, uint8_t data); diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index d4024ec247..522aa0777d 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -95,13 +95,13 @@ public: AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port); // Methods - bool read(); + bool read() override; - AP_GPS::GPS_Status highest_supported_status(void) { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } + AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; } static bool _detect(struct UBLOX_detect_state &state, uint8_t data); - bool is_configured(void) { + bool is_configured(void) override { #if CONFIG_HAL_BOARD != HAL_BOARD_SITL if (!gps._auto_config) { return true;