mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL_SITL: add missing override keywords
This commit is contained in:
parent
7184d5e860
commit
03e9becfcf
@ -12,16 +12,16 @@ public:
|
|||||||
ADCSource(SITL_State *sitlState, int16_t pin);
|
ADCSource(SITL_State *sitlState, int16_t pin);
|
||||||
|
|
||||||
/* implement AnalogSource virtual api: */
|
/* implement AnalogSource virtual api: */
|
||||||
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;
|
||||||
float voltage_average();
|
float voltage_average() override;
|
||||||
float voltage_latest();
|
float voltage_latest() override;
|
||||||
float voltage_average_ratiometric() {
|
float voltage_average_ratiometric() override {
|
||||||
return voltage_average();
|
return voltage_average();
|
||||||
}
|
}
|
||||||
void set_stop_pin(uint8_t pin) {}
|
void set_stop_pin(uint8_t pin) override {}
|
||||||
void set_settle_time(uint16_t settle_time_ms) {}
|
void set_settle_time(uint16_t settle_time_ms) override {}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SITL_State *_sitlState;
|
SITL_State *_sitlState;
|
||||||
@ -33,9 +33,9 @@ private:
|
|||||||
class HALSITL::AnalogIn : public AP_HAL::AnalogIn {
|
class HALSITL::AnalogIn : public AP_HAL::AnalogIn {
|
||||||
public:
|
public:
|
||||||
explicit AnalogIn(SITL_State *sitlState): _sitlState(sitlState) {}
|
explicit AnalogIn(SITL_State *sitlState): _sitlState(sitlState) {}
|
||||||
void init();
|
void init() override;
|
||||||
AP_HAL::AnalogSource* channel(int16_t n);
|
AP_HAL::AnalogSource* channel(int16_t n) override;
|
||||||
float board_voltage(void) {
|
float board_voltage(void) override {
|
||||||
return 5.0f;
|
return 5.0f;
|
||||||
}
|
}
|
||||||
private:
|
private:
|
||||||
|
@ -5,17 +5,17 @@
|
|||||||
class HALSITL::GPIO : public AP_HAL::GPIO {
|
class HALSITL::GPIO : public AP_HAL::GPIO {
|
||||||
public:
|
public:
|
||||||
explicit GPIO(SITL_State *sitlState): _sitlState(sitlState) {}
|
explicit GPIO(SITL_State *sitlState): _sitlState(sitlState) {}
|
||||||
void init();
|
void init() override;
|
||||||
void pinMode(uint8_t pin, uint8_t output);
|
void pinMode(uint8_t pin, uint8_t output) override;
|
||||||
uint8_t read(uint8_t pin);
|
uint8_t read(uint8_t pin) override;
|
||||||
void write(uint8_t pin, uint8_t value);
|
void write(uint8_t pin, uint8_t value) override;
|
||||||
void toggle(uint8_t pin);
|
void toggle(uint8_t pin) override;
|
||||||
|
|
||||||
/* Alternative interface: */
|
/* Alternative interface: */
|
||||||
AP_HAL::DigitalSource* channel(uint16_t n);
|
AP_HAL::DigitalSource* channel(uint16_t n) override;
|
||||||
|
|
||||||
/* return true if USB cable is connected */
|
/* return true if USB cable is connected */
|
||||||
bool usb_connected(void);
|
bool usb_connected(void) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SITL_State *_sitlState;
|
SITL_State *_sitlState;
|
||||||
@ -24,10 +24,10 @@ private:
|
|||||||
class HALSITL::DigitalSource : public AP_HAL::DigitalSource {
|
class HALSITL::DigitalSource : public AP_HAL::DigitalSource {
|
||||||
public:
|
public:
|
||||||
explicit DigitalSource(uint8_t pin);
|
explicit DigitalSource(uint8_t pin);
|
||||||
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 _pin;
|
uint8_t _pin;
|
||||||
|
@ -10,9 +10,9 @@
|
|||||||
class HALSITL::Semaphore : public AP_HAL::Semaphore {
|
class HALSITL::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;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user