From d4601862bc10c86b74ce048ce393db882507c675 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 7 Nov 2018 21:59:10 +1100 Subject: [PATCH] AP_HAL_Empty: add override keyword where required --- libraries/AP_HAL_Empty/AnalogIn.h | 22 +++++++++++----------- libraries/AP_HAL_Empty/GPIO.h | 22 +++++++++++----------- libraries/AP_HAL_Empty/I2CDevice.h | 4 ++-- libraries/AP_HAL_Empty/OpticalFlow.h | 8 ++++---- libraries/AP_HAL_Empty/RCInput.h | 10 +++++----- libraries/AP_HAL_Empty/RCOutput.h | 16 ++++++++-------- libraries/AP_HAL_Empty/SPIDevice.h | 2 +- libraries/AP_HAL_Empty/Scheduler.h | 16 ++++++++-------- libraries/AP_HAL_Empty/Semaphores.h | 6 +++--- libraries/AP_HAL_Empty/Storage.h | 6 +++--- libraries/AP_HAL_Empty/UARTDriver.h | 18 +++++++++--------- libraries/AP_HAL_Empty/Util.h | 2 +- 12 files changed, 66 insertions(+), 66 deletions(-) diff --git a/libraries/AP_HAL_Empty/AnalogIn.h b/libraries/AP_HAL_Empty/AnalogIn.h index 24d33c03eb..fdcd990845 100644 --- a/libraries/AP_HAL_Empty/AnalogIn.h +++ b/libraries/AP_HAL_Empty/AnalogIn.h @@ -5,14 +5,14 @@ class Empty::AnalogSource : public AP_HAL::AnalogSource { public: AnalogSource(float v); - float read_average(); - float read_latest(); - void set_pin(uint8_t p); - void set_stop_pin(uint8_t p); - void set_settle_time(uint16_t settle_time_ms); - float voltage_average(); - float voltage_latest(); - float voltage_average_ratiometric() { return voltage_average(); } + float read_average() override; + float read_latest() override; + void set_pin(uint8_t p) override; + void set_stop_pin(uint8_t p) override; + void set_settle_time(uint16_t settle_time_ms) override; + float voltage_average() override; + float voltage_latest() override; + float voltage_average_ratiometric() override { return voltage_average(); } private: float _v; }; @@ -20,7 +20,7 @@ private: class Empty::AnalogIn : public AP_HAL::AnalogIn { public: AnalogIn(); - void init(); - AP_HAL::AnalogSource* channel(int16_t n); - float board_voltage(void); + void init() override; + AP_HAL::AnalogSource* channel(int16_t n) override; + float board_voltage(void) override; }; diff --git a/libraries/AP_HAL_Empty/GPIO.h b/libraries/AP_HAL_Empty/GPIO.h index 2148eb546d..e66250ce5e 100644 --- a/libraries/AP_HAL_Empty/GPIO.h +++ b/libraries/AP_HAL_Empty/GPIO.h @@ -5,26 +5,26 @@ class Empty::GPIO : public AP_HAL::GPIO { public: GPIO(); - void init(); - void pinMode(uint8_t pin, uint8_t output); - uint8_t read(uint8_t pin); - void write(uint8_t pin, uint8_t value); - void toggle(uint8_t pin); + void init() override; + void pinMode(uint8_t pin, uint8_t output) override; + uint8_t read(uint8_t pin) override; + void write(uint8_t pin, uint8_t value) override; + void toggle(uint8_t pin) override; /* Alternative interface: */ - AP_HAL::DigitalSource* channel(uint16_t n); + AP_HAL::DigitalSource* channel(uint16_t n) override; /* return true if USB cable is connected */ - bool usb_connected(void); + bool usb_connected(void) override; }; class Empty::DigitalSource : public AP_HAL::DigitalSource { public: DigitalSource(uint8_t v); - void mode(uint8_t output); - uint8_t read(); - void write(uint8_t value); - void toggle(); + void mode(uint8_t output) override; + uint8_t read() override; + void write(uint8_t value) override; + void toggle() override; private: uint8_t _v; }; diff --git a/libraries/AP_HAL_Empty/I2CDevice.h b/libraries/AP_HAL_Empty/I2CDevice.h index 592b87d81c..7f51e85ce0 100644 --- a/libraries/AP_HAL_Empty/I2CDevice.h +++ b/libraries/AP_HAL_Empty/I2CDevice.h @@ -51,7 +51,7 @@ public: } bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, - uint32_t recv_len, uint8_t times) + uint32_t recv_len, uint8_t times) override { return true; } @@ -61,7 +61,7 @@ public: bool set_speed(enum AP_HAL::Device::Speed speed) override { return true; } /* See AP_HAL::Device::get_semaphore() */ - AP_HAL::Semaphore *get_semaphore() { return nullptr; } + AP_HAL::Semaphore *get_semaphore() override { return nullptr; } /* See AP_HAL::Device::register_periodic_callback() */ AP_HAL::Device::PeriodicHandle register_periodic_callback( diff --git a/libraries/AP_HAL_Empty/OpticalFlow.h b/libraries/AP_HAL_Empty/OpticalFlow.h index e792d23e3a..7f11e29054 100644 --- a/libraries/AP_HAL_Empty/OpticalFlow.h +++ b/libraries/AP_HAL_Empty/OpticalFlow.h @@ -16,8 +16,8 @@ class Empty::OpticalFlow : public AP_HAL::OpticalFlow { public: - void init() { } - bool read(Data_Frame& frame) { return false; } - void push_gyro(float gyro_x, float gyro_y, float dt) { }; - void push_gyro_bias(float gyro_bias_x, float gyro_bias_y) { } + void init() override { } + bool read(Data_Frame& frame) override { return false; } + void push_gyro(float gyro_x, float gyro_y, float dt) override { }; + void push_gyro_bias(float gyro_bias_x, float gyro_bias_y) override { } }; diff --git a/libraries/AP_HAL_Empty/RCInput.h b/libraries/AP_HAL_Empty/RCInput.h index 6171b5fa05..ecde9697c7 100644 --- a/libraries/AP_HAL_Empty/RCInput.h +++ b/libraries/AP_HAL_Empty/RCInput.h @@ -5,9 +5,9 @@ class Empty::RCInput : public AP_HAL::RCInput { public: RCInput(); - void init(); - bool new_input(); - uint8_t num_channels(); - uint16_t read(uint8_t ch); - uint8_t read(uint16_t* periods, uint8_t len); + void init() override; + bool new_input() override; + uint8_t num_channels() override; + uint16_t read(uint8_t ch) override; + uint8_t read(uint16_t* periods, uint8_t len) override; }; diff --git a/libraries/AP_HAL_Empty/RCOutput.h b/libraries/AP_HAL_Empty/RCOutput.h index 84c0e76a8a..18a823c3f5 100644 --- a/libraries/AP_HAL_Empty/RCOutput.h +++ b/libraries/AP_HAL_Empty/RCOutput.h @@ -3,14 +3,14 @@ #include "AP_HAL_Empty.h" class Empty::RCOutput : public AP_HAL::RCOutput { - void init(); - void set_freq(uint32_t chmask, uint16_t freq_hz); - uint16_t get_freq(uint8_t ch); - void enable_ch(uint8_t ch); - void disable_ch(uint8_t ch); - void write(uint8_t ch, uint16_t period_us); - uint16_t read(uint8_t ch); - void read(uint16_t* period_us, uint8_t len); + void init() override; + void set_freq(uint32_t chmask, uint16_t freq_hz) override; + uint16_t get_freq(uint8_t ch) override; + void enable_ch(uint8_t ch) override; + void disable_ch(uint8_t ch) override; + void write(uint8_t ch, uint16_t period_us) override; + uint16_t read(uint8_t ch) override; + void read(uint16_t* period_us, uint8_t len) override; void cork(void) override {} void push(void) override {} }; diff --git a/libraries/AP_HAL_Empty/SPIDevice.h b/libraries/AP_HAL_Empty/SPIDevice.h index 4e297caa6c..be25c2873c 100644 --- a/libraries/AP_HAL_Empty/SPIDevice.h +++ b/libraries/AP_HAL_Empty/SPIDevice.h @@ -56,7 +56,7 @@ public: } /* See AP_HAL::Device::get_semaphore() */ - AP_HAL::Semaphore *get_semaphore() + AP_HAL::Semaphore *get_semaphore() override { return &_semaphore; } diff --git a/libraries/AP_HAL_Empty/Scheduler.h b/libraries/AP_HAL_Empty/Scheduler.h index 70dde7fd6b..13e6fe164b 100644 --- a/libraries/AP_HAL_Empty/Scheduler.h +++ b/libraries/AP_HAL_Empty/Scheduler.h @@ -5,16 +5,16 @@ class Empty::Scheduler : public AP_HAL::Scheduler { public: Scheduler(); - void init(); - void delay(uint16_t ms); - void delay_microseconds(uint16_t us); - void register_timer_process(AP_HAL::MemberProc); - void register_io_process(AP_HAL::MemberProc); + void init() override; + void delay(uint16_t ms) override; + void delay_microseconds(uint16_t us) override; + void register_timer_process(AP_HAL::MemberProc) override; + void register_io_process(AP_HAL::MemberProc) override; - void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us); + void register_timer_failsafe(AP_HAL::Proc, uint32_t period_us) override; - void system_initialized(); + void system_initialized() override; - void reboot(bool hold_in_bootloader); + void reboot(bool hold_in_bootloader) override; }; diff --git a/libraries/AP_HAL_Empty/Semaphores.h b/libraries/AP_HAL_Empty/Semaphores.h index cb89c197bd..c2f8618a22 100644 --- a/libraries/AP_HAL_Empty/Semaphores.h +++ b/libraries/AP_HAL_Empty/Semaphores.h @@ -5,9 +5,9 @@ class Empty::Semaphore : public AP_HAL::Semaphore { public: Semaphore() : _taken(false) {} - bool give(); - bool take(uint32_t timeout_ms); - bool take_nonblocking(); + bool give() override; + bool take(uint32_t timeout_ms) override; + bool take_nonblocking() override; private: bool _taken; }; diff --git a/libraries/AP_HAL_Empty/Storage.h b/libraries/AP_HAL_Empty/Storage.h index dd01cbea5a..d709c723b6 100644 --- a/libraries/AP_HAL_Empty/Storage.h +++ b/libraries/AP_HAL_Empty/Storage.h @@ -5,7 +5,7 @@ class Empty::Storage : public AP_HAL::Storage { public: Storage(); - void init(); - void read_block(void *dst, uint16_t src, size_t n); - void write_block(uint16_t dst, const void* src, size_t n); + void init() override; + void read_block(void *dst, uint16_t src, size_t n) override; + void write_block(uint16_t dst, const void* src, size_t n) override; }; diff --git a/libraries/AP_HAL_Empty/UARTDriver.h b/libraries/AP_HAL_Empty/UARTDriver.h index 987472ab86..d45f39d62d 100644 --- a/libraries/AP_HAL_Empty/UARTDriver.h +++ b/libraries/AP_HAL_Empty/UARTDriver.h @@ -6,13 +6,13 @@ class Empty::UARTDriver : public AP_HAL::UARTDriver { public: UARTDriver(); /* Empty implementations of UARTDriver virtual methods */ - void begin(uint32_t b); - void begin(uint32_t b, uint16_t rxS, uint16_t txS); - void end(); - void flush(); - bool is_initialized(); - void set_blocking_writes(bool blocking); - bool tx_pending(); + void begin(uint32_t b) override; + void begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + void end() override; + void flush() override; + bool is_initialized() override; + void set_blocking_writes(bool blocking) override; + bool tx_pending() override; /* Empty implementations of Stream virtual methods */ uint32_t available() override; @@ -20,6 +20,6 @@ public: int16_t read() override; /* Empty implementations of Print virtual methods */ - size_t write(uint8_t c); - size_t write(const uint8_t *buffer, size_t size); + size_t write(uint8_t c) override; + size_t write(const uint8_t *buffer, size_t size) override; }; diff --git a/libraries/AP_HAL_Empty/Util.h b/libraries/AP_HAL_Empty/Util.h index f461d2c482..3dae90c2f8 100644 --- a/libraries/AP_HAL_Empty/Util.h +++ b/libraries/AP_HAL_Empty/Util.h @@ -5,5 +5,5 @@ class Empty::Util : public AP_HAL::Util { public: - bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } + bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; } };