From e0ab431ebd2692ab5f95e0d7a1bdd5ad44652dfc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Nov 2018 22:01:30 +1100 Subject: [PATCH] AP_Proximity: add override keyword where required --- libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h | 6 +++--- libraries/AP_Proximity/AP_Proximity_MAV.h | 8 ++++---- libraries/AP_Proximity/AP_Proximity_RPLidarA2.h | 6 +++--- libraries/AP_Proximity/AP_Proximity_RangeFinder.h | 8 ++++---- libraries/AP_Proximity/AP_Proximity_SITL.h | 6 +++--- libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h | 6 +++--- libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h | 6 +++--- 7 files changed, 23 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h index 246a8cc06f..562960a486 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h @@ -16,11 +16,11 @@ public: static bool detect(AP_SerialManager &serial_manager); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const; - float distance_min() const; + float distance_max() const override; + float distance_min() const override; private: diff --git a/libraries/AP_Proximity/AP_Proximity_MAV.h b/libraries/AP_Proximity/AP_Proximity_MAV.h index 1bd86909e1..d558bd97d9 100644 --- a/libraries/AP_Proximity/AP_Proximity_MAV.h +++ b/libraries/AP_Proximity/AP_Proximity_MAV.h @@ -11,14 +11,14 @@ public: AP_Proximity_MAV(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const { return _distance_max; } - float distance_min() const { return _distance_min; }; + float distance_max() const override { return _distance_max; } + float distance_min() const override { return _distance_min; }; // get distance upwards in meters. returns true on success - bool get_upward_distance(float &distance) const; + bool get_upward_distance(float &distance) const override; // handle mavlink DISTANCE_SENSOR messages void handle_msg(mavlink_message_t *msg) override; diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h index 0ad2d641e0..d75936e381 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h @@ -45,11 +45,11 @@ public: static bool detect(AP_SerialManager &serial_manager); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const; - float distance_min() const; + float distance_max() const override; + float distance_min() const override; private: enum rp_state { diff --git a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h index 7f5dbf36ec..f6d7ed59f5 100644 --- a/libraries/AP_Proximity/AP_Proximity_RangeFinder.h +++ b/libraries/AP_Proximity/AP_Proximity_RangeFinder.h @@ -13,14 +13,14 @@ public: AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const { return _distance_max; } - float distance_min() const { return _distance_min; } + float distance_max() const override { return _distance_max; } + float distance_min() const override { return _distance_min; } // get distance upwards in meters. returns true on success - bool get_upward_distance(float &distance) const; + bool get_upward_distance(float &distance) const override; private: diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.h b/libraries/AP_Proximity/AP_Proximity_SITL.h index dd20a2a856..1922d65bf6 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.h +++ b/libraries/AP_Proximity/AP_Proximity_SITL.h @@ -17,11 +17,11 @@ public: void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const; - float distance_min() const; + float distance_max() const override; + float distance_min() const override; // get distance upwards in meters. returns true on success - bool get_upward_distance(float &distance) const; + bool get_upward_distance(float &distance) const override; private: SITL::SITL *sitl; diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h index 9d7dbe6ee9..ff9474fb6b 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.h @@ -16,11 +16,11 @@ public: static bool detect(AP_SerialManager &serial_manager); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const; - float distance_min() const; + float distance_max() const override; + float distance_min() const override; private: diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h index d215ab467a..c64cb7e1c1 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTowerEvo.h @@ -15,11 +15,11 @@ public: static bool detect(AP_SerialManager &serial_manager); // update state - void update(void); + void update(void) override; // get maximum and minimum distances (in meters) of sensor - float distance_max() const; - float distance_min() const; + float distance_max() const override; + float distance_min() const override; private: