AP_GPS: add override keyword where required
This commit is contained in:
parent
e7a981d2c3
commit
fd888727b8
@ -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);
|
||||
|
||||
|
@ -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"; }
|
||||
|
||||
|
@ -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"; }
|
||||
|
||||
|
@ -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);
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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;
|
||||
|
||||
|
@ -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"; }
|
||||
|
||||
|
@ -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;
|
||||
|
||||
|
@ -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);
|
||||
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user