AP_HAL_Linux: add missing override keywords

This commit is contained in:
Peter Barker 2019-02-22 10:08:12 +11:00 committed by Francisco Ferreira
parent 03e9becfcf
commit eb73a14da8
24 changed files with 121 additions and 121 deletions

View File

@ -9,14 +9,14 @@ class AnalogSource_ADS1115: public AP_HAL::AnalogSource {
public: public:
friend class AnalogIn_ADS1115; friend class AnalogIn_ADS1115;
AnalogSource_ADS1115(int16_t pin); AnalogSource_ADS1115(int16_t pin);
float read_average(); float read_average() override;
float read_latest(); float read_latest() override;
void set_pin(uint8_t p); void set_pin(uint8_t p) override;
void set_stop_pin(uint8_t p) {} void set_stop_pin(uint8_t p) override {}
void set_settle_time(uint16_t settle_time_ms){} void set_settle_time(uint16_t settle_time_ms) override {}
float voltage_average(); float voltage_average() override;
float voltage_latest(); float voltage_latest() override;
float voltage_average_ratiometric(); float voltage_average_ratiometric() override;
private: private:
int16_t _pin; int16_t _pin;
float _value; float _value;

View File

@ -25,14 +25,14 @@ class AnalogSource_IIO : public AP_HAL::AnalogSource {
public: public:
friend class AnalogIn_IIO; friend class AnalogIn_IIO;
AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling); AnalogSource_IIO(int16_t pin, float initial_value, float voltage_scaling);
float read_average(); float read_average() override;
float read_latest(); float read_latest() override;
void set_pin(uint8_t p); void set_pin(uint8_t p) override;
void set_stop_pin(uint8_t p); void set_stop_pin(uint8_t p) override;
void set_settle_time(uint16_t settle_time_ms); void set_settle_time(uint16_t settle_time_ms) override;
float voltage_average(); float voltage_average() override;
float voltage_latest(); float voltage_latest() override;
float voltage_average_ratiometric() { return voltage_average(); } float voltage_average_ratiometric() override { return voltage_average(); }
private: private:
float _value; float _value;
float _latest; float _latest;
@ -53,9 +53,9 @@ private:
class AnalogIn_IIO : public AP_HAL::AnalogIn { class AnalogIn_IIO : public AP_HAL::AnalogIn {
public: public:
AnalogIn_IIO(); AnalogIn_IIO();
void init(); void init() override;
AP_HAL::AnalogSource* channel(int16_t n); AP_HAL::AnalogSource* channel(int16_t n) override;
// we don't yet know how to get the board voltage // we don't yet know how to get the board voltage
float board_voltage(void) { return 5.0f; } float board_voltage(void) override { return 5.0f; }
}; };

View File

@ -7,10 +7,10 @@ namespace Linux {
class DigitalSource : public AP_HAL::DigitalSource { class DigitalSource : public AP_HAL::DigitalSource {
public: public:
DigitalSource(uint8_t v); DigitalSource(uint8_t v);
void mode(uint8_t output); void mode(uint8_t output) override;
uint8_t read(); uint8_t read() override;
void write(uint8_t value); void write(uint8_t value) override;
void toggle(); void toggle() override;
private: private:
uint8_t _v; uint8_t _v;

View File

@ -11,10 +11,10 @@ class DigitalSource_Sysfs : public AP_HAL::DigitalSource {
friend class GPIO_Sysfs; friend class GPIO_Sysfs;
public: public:
~DigitalSource_Sysfs(); ~DigitalSource_Sysfs();
uint8_t read(); uint8_t read() override;
void write(uint8_t value); void write(uint8_t value) override;
void mode(uint8_t output); void mode(uint8_t output) override;
void toggle(); void toggle() override;
private: private:
/* Only GPIO_Sysfs will be able to instantiate */ /* Only GPIO_Sysfs will be able to instantiate */
DigitalSource_Sysfs(unsigned pin, int value_fd); DigitalSource_Sysfs(unsigned pin, int value_fd);
@ -36,7 +36,7 @@ public:
return static_cast<GPIO_Sysfs*>(gpio); return static_cast<GPIO_Sysfs*>(gpio);
} }
void init(); void init() override;
void pinMode(uint8_t vpin, uint8_t output) override; void pinMode(uint8_t vpin, uint8_t output) override;
uint8_t read(uint8_t vpin) override; uint8_t read(uint8_t vpin) override;

View File

@ -36,10 +36,10 @@ public:
class OpticalFlow_Onboard : public AP_HAL::OpticalFlow { class OpticalFlow_Onboard : public AP_HAL::OpticalFlow {
public: public:
void init(); void init() override;
bool read(AP_HAL::OpticalFlow::Data_Frame& frame); bool read(AP_HAL::OpticalFlow::Data_Frame& frame) override;
void push_gyro(float gyro_x, float gyro_y, float dt); void push_gyro(float gyro_x, float gyro_y, float dt) override;
void push_gyro_bias(float gyro_bias_x, float gyro_bias_y); void push_gyro_bias(float gyro_bias_x, float gyro_bias_y) override;
private: private:
void _run_optflow(); void _run_optflow();

View File

@ -16,12 +16,12 @@ public:
return static_cast<RCInput*>(rcinput); return static_cast<RCInput*>(rcinput);
} }
virtual void init(); virtual void init() override;
bool new_input(); bool new_input() override;
uint8_t num_channels(); uint8_t num_channels() override;
void set_num_channels(uint8_t num); void set_num_channels(uint8_t num);
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
uint8_t read(uint16_t* periods, uint8_t len); uint8_t read(uint16_t* periods, uint8_t len) override;
int16_t get_rssi(void) override { int16_t get_rssi(void) override {
return _rssi; return _rssi;

View File

@ -30,8 +30,8 @@ namespace Linux {
class RCInput_AioPRU : public RCInput { class RCInput_AioPRU : public RCInput {
public: public:
void init(); void init() override;
void _timer_tick(void); void _timer_tick(void) override;
protected: protected:
static const uint32_t TICK_PER_US = 200; static const uint32_t TICK_PER_US = 200;

View File

@ -14,8 +14,8 @@ namespace Linux {
class RCInput_PRU : public RCInput { class RCInput_PRU : public RCInput {
public: public:
void init(); void init() override;
void _timer_tick(void); void _timer_tick(void) override;
private: private:
static const unsigned int NUM_RING_ENTRIES=300; static const unsigned int NUM_RING_ENTRIES=300;

View File

@ -82,8 +82,8 @@ public:
class RCInput_RPI : public RCInput class RCInput_RPI : public RCInput
{ {
public: public:
void init(); void init() override;
void _timer_tick(void); void _timer_tick(void) override;
RCInput_RPI(); RCInput_RPI();
~RCInput_RPI(); ~RCInput_RPI();

View File

@ -30,8 +30,8 @@ class RCInput_SoloLink : public RCInput
public: public:
RCInput_SoloLink(); RCInput_SoloLink();
void init(); void init() override;
void _timer_tick(); void _timer_tick() override;
private: private:
static const unsigned int PACKET_LEN = 26; static const unsigned int PACKET_LEN = 26;

View File

@ -12,8 +12,8 @@ class RCInput_UDP : public RCInput
{ {
public: public:
RCInput_UDP(); RCInput_UDP();
void init(); void init() override;
void _timer_tick(void); void _timer_tick(void) override;
private: private:
SocketAPM _socket{true}; SocketAPM _socket{true};
uint16_t _port; uint16_t _port;

View File

@ -11,8 +11,8 @@ namespace Linux {
class RCInput_ZYNQ : public RCInput { class RCInput_ZYNQ : public RCInput {
public: public:
void init(); void init() override;
void _timer_tick(void); void _timer_tick(void) override;
private: private:
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ

View File

@ -25,14 +25,14 @@
namespace Linux { namespace Linux {
class RCOutput_AioPRU : public AP_HAL::RCOutput { class RCOutput_AioPRU : public AP_HAL::RCOutput {
void init(); void init() override;
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch); void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us); void write(uint8_t ch, uint16_t period_us) override;
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
void read(uint16_t* period_us, uint8_t len); void read(uint16_t* period_us, uint8_t len) override;
void cork(void) override; void cork(void) override;
void push(void) override; void push(void) override;

View File

@ -20,17 +20,17 @@ public:
int16_t oe_pin_number); int16_t oe_pin_number);
~RCOutput_PCA9685(); ~RCOutput_PCA9685();
void init(); void init() override;
void reset_all_channels(); void reset_all_channels();
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch); void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us); void write(uint8_t ch, uint16_t period_us) override;
void cork() override; void cork() override;
void push() override; void push() override;
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
void read(uint16_t* period_us, uint8_t len); void read(uint16_t* period_us, uint8_t len) override;
private: private:
void reset(); void reset();

View File

@ -16,14 +16,14 @@
namespace Linux { namespace Linux {
class RCOutput_PRU : public AP_HAL::RCOutput { class RCOutput_PRU : public AP_HAL::RCOutput {
void init(); void init() override;
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch); void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us); void write(uint8_t ch, uint16_t period_us) override;
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
void read(uint16_t* period_us, uint8_t len); void read(uint16_t* period_us, uint8_t len) override;
void cork(void) override; void cork(void) override;
void push(void) override; void push(void) override;

View File

@ -15,14 +15,14 @@ public:
return static_cast<RCOutput_Sysfs *>(rcoutput); return static_cast<RCOutput_Sysfs *>(rcoutput);
} }
void init(); void init() override;
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch); void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us); void write(uint8_t ch, uint16_t period_us) override;
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
void read(uint16_t *period_us, uint8_t len); void read(uint16_t *period_us, uint8_t len) override;
void cork(void) override; void cork(void) override;
void push(void) override; void push(void) override;

View File

@ -8,14 +8,14 @@ namespace Linux {
class RCOutput_ZYNQ : public AP_HAL::RCOutput { class RCOutput_ZYNQ : public AP_HAL::RCOutput {
public: public:
void init(); void init() override;
void set_freq(uint32_t chmask, uint16_t freq_hz); void set_freq(uint32_t chmask, uint16_t freq_hz) override;
uint16_t get_freq(uint8_t ch); uint16_t get_freq(uint8_t ch) override;
void enable_ch(uint8_t ch); void enable_ch(uint8_t ch) override;
void disable_ch(uint8_t ch); void disable_ch(uint8_t ch) override;
void write(uint8_t ch, uint16_t period_us); void write(uint8_t ch, uint16_t period_us) override;
uint16_t read(uint8_t ch); uint16_t read(uint8_t ch) override;
void read(uint16_t* period_us, uint8_t len); void read(uint16_t* period_us, uint8_t len) override;
void cork(void) override; void cork(void) override;
void push(void) override; void push(void) override;

View File

@ -90,7 +90,7 @@ public:
} }
/* AP_HAL::SPIDeviceManager implementation */ /* AP_HAL::SPIDeviceManager implementation */
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name); AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) override;
/* /*
* Stop all SPI threads and block until they are finalized. This doesn't * Stop all SPI threads and block until they are finalized. This doesn't
@ -100,10 +100,10 @@ public:
void teardown(); void teardown();
/* See AP_HAL::SPIDeviceManager::get_count() */ /* See AP_HAL::SPIDeviceManager::get_count() */
uint8_t get_count(); uint8_t get_count() override;
/* See AP_HAL::SPIDeviceManager::get_device_name() */ /* See AP_HAL::SPIDeviceManager::get_device_name() */
const char *get_device_name(uint8_t idx); const char *get_device_name(uint8_t idx) override;
protected: protected:
void _unregister(SPIBus &b); void _unregister(SPIBus &b);

View File

@ -9,12 +9,12 @@ namespace Linux {
class SPIUARTDriver : public UARTDriver { class SPIUARTDriver : public UARTDriver {
public: public:
SPIUARTDriver(); SPIUARTDriver();
void begin(uint32_t b, uint16_t rxS, uint16_t txS); void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void _timer_tick(void); void _timer_tick(void) override;
protected: protected:
int _write_fd(const uint8_t *buf, uint16_t n); int _write_fd(const uint8_t *buf, uint16_t n) override;
int _read_fd(uint8_t *buf, uint16_t n); int _read_fd(uint8_t *buf, uint16_t n) override;
AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev; AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev;

View File

@ -24,22 +24,22 @@ public:
return static_cast<Scheduler*>(scheduler); return static_cast<Scheduler*>(scheduler);
} }
void init(); void init() override;
void delay(uint16_t ms); void delay(uint16_t ms) override;
void delay_microseconds(uint16_t us); void delay_microseconds(uint16_t us) override;
void register_timer_process(AP_HAL::MemberProc); void register_timer_process(AP_HAL::MemberProc) override;
void register_io_process(AP_HAL::MemberProc); void register_io_process(AP_HAL::MemberProc) override;
bool in_main_thread() const override; bool in_main_thread() const 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;
void stop_clock(uint64_t time_usec); void stop_clock(uint64_t time_usec) override;
uint64_t stopped_clock_usec() const { return _stopped_clock_usec; } uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }

View File

@ -11,9 +11,9 @@ namespace Linux {
class Semaphore : public AP_HAL::Semaphore { class Semaphore : public AP_HAL::Semaphore {
public: public:
Semaphore(); Semaphore();
bool give(); bool give() override;
bool take(uint32_t timeout_ms); bool take(uint32_t timeout_ms) override;
bool take_nonblocking(); bool take_nonblocking() override;
protected: protected:
pthread_mutex_t _lock; pthread_mutex_t _lock;
}; };

View File

@ -25,12 +25,12 @@ public:
uint8_t read_byte(uint16_t loc); uint8_t read_byte(uint16_t loc);
uint16_t read_word(uint16_t loc); uint16_t read_word(uint16_t loc);
uint32_t read_dword(uint16_t loc); uint32_t read_dword(uint16_t loc);
void read_block(void *dst, uint16_t src, size_t n); void read_block(void *dst, uint16_t src, size_t n) override;
void write_byte(uint16_t loc, uint8_t value); void write_byte(uint16_t loc, uint8_t value);
void write_word(uint16_t loc, uint16_t value); void write_word(uint16_t loc, uint16_t value);
void write_dword(uint16_t loc, uint32_t value); void write_dword(uint16_t loc, uint32_t value);
void write_block(uint16_t dst, const void* src, size_t n); void write_block(uint16_t dst, const void* src, size_t n) override;
virtual void _timer_tick(void) override; virtual void _timer_tick(void) override;

View File

@ -18,13 +18,13 @@ public:
} }
/* Linux implementations of UARTDriver virtual methods */ /* Linux implementations of UARTDriver virtual methods */
void begin(uint32_t b); void begin(uint32_t b) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS); void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end(); void end() override;
void flush(); void flush() override;
bool is_initialized(); bool is_initialized() override;
void set_blocking_writes(bool blocking); void set_blocking_writes(bool blocking) override;
bool tx_pending(); bool tx_pending() override;
/* Linux implementations of Stream virtual methods */ /* Linux implementations of Stream virtual methods */
uint32_t available() override; uint32_t available() override;
@ -32,8 +32,8 @@ public:
int16_t read() override; int16_t read() override;
/* Linux implementations of Print virtual methods */ /* Linux implementations of Print virtual methods */
size_t write(uint8_t c); size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size); size_t write(const uint8_t *buffer, size_t size) override;
void set_device_path(const char *path); void set_device_path(const char *path);

View File

@ -29,12 +29,12 @@ public:
} }
void init(int argc, char *const *argv); void init(int argc, char *const *argv);
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; }
/** /**
return commandline arguments, if available return commandline arguments, if available
*/ */
void commandline_arguments(uint8_t &argc, char * const *&argv); void commandline_arguments(uint8_t &argc, char * const *&argv) override;
/* /*
set system clock in UTC microseconds set system clock in UTC microseconds