From be53782ef101e2102b99b70026db4bbcb785a549 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Nov 2018 22:01:07 +1100 Subject: [PATCH] AP_Mount: add override keyword where required --- libraries/AP_Mount/AP_Mount_Alexmos.h | 8 ++++---- libraries/AP_Mount/AP_Mount_SToRM32.h | 8 ++++---- libraries/AP_Mount/AP_Mount_SToRM32_serial.h | 10 +++++----- libraries/AP_Mount/AP_Mount_Servo.h | 8 ++++---- libraries/AP_Mount/AP_Mount_SoloGimbal.h | 10 +++++----- libraries/AP_Mount/SoloGimbal.h | 8 ++++---- 6 files changed, 26 insertions(+), 26 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index f08924239a..1c87530c3c 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -71,16 +71,16 @@ public: {} // init - performs any required initialisation for this instance - virtual void init(const AP_SerialManager& serial_manager); + virtual void init(const AP_SerialManager& serial_manager) override; // update mount position - should be called periodically - virtual void update(); + virtual void update() override; // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - virtual bool has_pan_control() const; + virtual bool has_pan_control() const override; // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode) ; + virtual void set_mode(enum MAV_MOUNT_MODE mode) override; // send_mount_status - called to allow mounts to send their status to GCS via MAVLink virtual void send_mount_status(mavlink_channel_t chan) override; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index d560f3ec1d..1a99965ef7 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -25,16 +25,16 @@ public: AP_Mount_SToRM32(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); // init - performs any required initialisation for this instance - virtual void init(const AP_SerialManager& serial_manager) {} + virtual void init(const AP_SerialManager& serial_manager) override {} // update mount position - should be called periodically - virtual void update(); + virtual void update() override; // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - virtual bool has_pan_control() const; + virtual bool has_pan_control() const override; // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode); + virtual void set_mode(enum MAV_MOUNT_MODE mode) override; // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message virtual void send_mount_status(mavlink_channel_t chan) override; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index f74bf151c2..0c8febe894 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -23,19 +23,19 @@ public: AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); // init - performs any required initialisation for this instance - virtual void init(const AP_SerialManager& serial_manager); + virtual void init(const AP_SerialManager& serial_manager) override; // update mount position - should be called periodically - virtual void update(); + virtual void update() override; // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - virtual bool has_pan_control() const; + virtual bool has_pan_control() const override; // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode); + virtual void set_mode(enum MAV_MOUNT_MODE mode) override; // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message - virtual void send_mount_status(mavlink_channel_t chan); + virtual void send_mount_status(mavlink_channel_t chan) override; private: diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index b5c7b9264a..ebda4065d8 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -25,16 +25,16 @@ public: } // init - performs any required initialisation for this instance - virtual void init(const AP_SerialManager& serial_manager); + virtual void init(const AP_SerialManager& serial_manager) override; // update mount position - should be called periodically - virtual void update(); + virtual void update() override; // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - virtual bool has_pan_control() const { return _flags.pan_control; } + virtual bool has_pan_control() const override { return _flags.pan_control; } // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode); + virtual void set_mode(enum MAV_MOUNT_MODE mode) override; // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message virtual void send_mount_status(mavlink_channel_t chan) override; diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 6e6cf9a5e0..2d424ecb8b 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -25,16 +25,16 @@ public: AP_Mount_SoloGimbal(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance); // init - performs any required initialisation for this instance - virtual void init(const AP_SerialManager& serial_manager); + virtual void init(const AP_SerialManager& serial_manager) override; // update mount position - should be called periodically - virtual void update(); + virtual void update() override; // has_pan_control - returns true if this mount can control it's pan (required for multicopters) - virtual bool has_pan_control() const; + virtual bool has_pan_control() const override; // set_mode - sets mount's mode - virtual void set_mode(enum MAV_MOUNT_MODE mode); + virtual void set_mode(enum MAV_MOUNT_MODE mode) override; // send_mount_status - called to allow mounts to send their status to GCS using the MOUNT_STATUS message virtual void send_mount_status(mavlink_channel_t chan) override; @@ -47,7 +47,7 @@ public: // send a GIMBAL_REPORT message to the GCS void send_gimbal_report(mavlink_channel_t chan) override; - virtual void update_fast(); + virtual void update_fast() override; private: // internal variables diff --git a/libraries/AP_Mount/SoloGimbal.h b/libraries/AP_Mount/SoloGimbal.h index f9e1102e42..5360f23ef7 100644 --- a/libraries/AP_Mount/SoloGimbal.h +++ b/libraries/AP_Mount/SoloGimbal.h @@ -95,10 +95,10 @@ private: void readVehicleDeltaAngle(uint8_t ins_index, Vector3f &dAng); - void _acal_save_calibrations(); - bool _acal_get_ready_to_sample(); - bool _acal_get_saving(); - AccelCalibrator* _acal_get_calibrator(uint8_t instance); + void _acal_save_calibrations() override; + bool _acal_get_ready_to_sample() override; + bool _acal_get_saving() override; + AccelCalibrator* _acal_get_calibrator(uint8_t instance) override; gimbal_mode_t get_mode();