AP_HAL_ChibiOS: add override keyword in many places

This commit is contained in:
Peter Barker 2018-11-07 21:58:46 +11:00 committed by Andrew Tridgell
parent c9f31f7e0a
commit 17f643719a
7 changed files with 42 additions and 42 deletions

View File

@ -30,14 +30,14 @@ class ChibiOS::AnalogSource : public AP_HAL::AnalogSource {
public:
friend class ChibiOS::AnalogIn;
AnalogSource(int16_t pin, float initial_value);
float read_average();
float read_latest();
void set_pin(uint8_t p);
float voltage_average();
float voltage_latest();
float voltage_average_ratiometric();
void set_stop_pin(uint8_t p) {}
void set_settle_time(uint16_t settle_time_ms) {}
float read_average() override;
float read_latest() override;
void set_pin(uint8_t p) override;
float voltage_average() override;
float voltage_latest() override;
float voltage_average_ratiometric() override;
void set_stop_pin(uint8_t p) override {}
void set_settle_time(uint16_t settle_time_ms) override {}
private:
// what value it has

View File

@ -29,14 +29,14 @@
class ChibiOS::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;
/* Interrupt interface - fast, for RCOutput and SPI radios */
bool attach_interrupt(uint8_t interrupt_num,
@ -66,10 +66,10 @@ private:
class ChibiOS::DigitalSource : public AP_HAL::DigitalSource {
public:
DigitalSource(ioline_t line);
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:
ioline_t line;
};

View File

@ -29,14 +29,14 @@
class ChibiOS::RCOutput : public AP_HAL::RCOutput {
public:
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;
uint16_t read_last_sent(uint8_t ch) override;
void read_last_sent(uint16_t* period_us, uint8_t len) override;
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
@ -129,7 +129,7 @@ public:
enable telemetry request for a mask of channels. This is used
with DShot to get telemetry feedback
*/
void set_telem_request_mask(uint16_t mask) { telem_request_mask = (mask >> chan_offset); }
void set_telem_request_mask(uint16_t mask) override { telem_request_mask = (mask >> chan_offset); }
/*
get safety switch state, used by Util.cpp

View File

@ -134,7 +134,7 @@ public:
return static_cast<SPIDeviceManager*>(spi_mgr);
}
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name);
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) override;
private:
static SPIDesc device_table[];

View File

@ -76,7 +76,7 @@ public:
/* AP_HAL::Scheduler methods */
void init();
void init() override;
void delay(uint16_t ms) override;
void delay_microseconds(uint16_t us) override;
void delay_microseconds_boost(uint16_t us) override;
@ -87,7 +87,7 @@ public:
void reboot(bool hold_in_bootloader) override;
bool in_main_thread() const override;
void system_initialized();
void system_initialized() override;
void hal_initialized() { _hal_initialized = true; }
bool check_called_boost(void);

View File

@ -36,9 +36,9 @@
class ChibiOS::Storage : public AP_HAL::Storage {
public:
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;
void _timer_tick(void) override;
bool healthy(void) override;

View File

@ -32,13 +32,13 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
public:
UARTDriver(uint8_t serial_num);
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;
uint32_t available() override;
@ -46,8 +46,8 @@ public:
int16_t read() override;
void _timer_tick(void) override;
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;
// lock a port for exclusive use. Use a key of 0 to unlock
bool lock_port(uint32_t key) override;