Browse Source

AP_HAL_SITL: add override keyword where required

mission-4.1.18
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
fdfe5ac75a
  1. 4
      libraries/AP_HAL_SITL/RCOutput.h
  2. 18
      libraries/AP_HAL_SITL/Scheduler.h
  3. 22
      libraries/AP_HAL_SITL/UARTDriver.h
  4. 2
      libraries/AP_HAL_SITL/Util.h

4
libraries/AP_HAL_SITL/RCOutput.h

@ -15,8 +15,8 @@ public: @@ -15,8 +15,8 @@ public:
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);
void push(void);
void cork(void) override;
void push(void) override;
private:
SITL_State *_sitlState;

18
libraries/AP_HAL_SITL/Scheduler.h

@ -18,19 +18,19 @@ public: @@ -18,19 +18,19 @@ public:
/* AP_HAL::Scheduler methods */
void init();
void delay(uint16_t ms);
void delay_microseconds(uint16_t us);
void init() override;
void delay(uint16_t ms) override;
void delay_microseconds(uint16_t us) override;
void register_timer_process(AP_HAL::MemberProc);
void register_io_process(AP_HAL::MemberProc);
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;
bool in_main_thread() const override;
void system_initialized();
void system_initialized() override;
void reboot(bool hold_in_bootloader);
void reboot(bool hold_in_bootloader) override;
bool interrupts_are_blocked(void) {
return _nested_atomic_ctr != 0;
@ -72,7 +72,7 @@ private: @@ -72,7 +72,7 @@ private:
static bool _in_timer_proc;
static bool _in_io_proc;
void stop_clock(uint64_t time_usec);
void stop_clock(uint64_t time_usec) override;
static void *thread_create_trampoline(void *ctx);
static void check_thread_stacks(void);

22
libraries/AP_HAL_SITL/UARTDriver.h

@ -26,22 +26,22 @@ public: @@ -26,22 +26,22 @@ public:
}
/* Implementations of UARTDriver virtual methods */
void begin(uint32_t b) {
void begin(uint32_t b) override {
begin(b, 0, 0);
}
void begin(uint32_t b, uint16_t rxS, uint16_t txS);
void end();
void flush();
bool is_initialized() {
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override {
return true;
}
void set_blocking_writes(bool blocking)
void set_blocking_writes(bool blocking) override
{
_nonblocking_writes = !blocking;
}
bool tx_pending() {
bool tx_pending() override {
return false;
}
@ -51,21 +51,21 @@ public: @@ -51,21 +51,21 @@ public:
int16_t read() override;
/* 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;
// file descriptor, exposed so SITL_State::loop_hook() can use it
int _fd;
bool _unbuffered_writes;
enum flow_control get_flow_control(void) { return FLOW_CONTROL_ENABLE; }
enum flow_control get_flow_control(void) override { return FLOW_CONTROL_ENABLE; }
void configure_parity(uint8_t v) override;
void set_stop_bits(int n) override;
bool set_unbuffered_writes(bool on) override;
void _timer_tick(void);
void _timer_tick(void) override;
/*
return timestamp estimate in microseconds for when the start of

2
libraries/AP_HAL_SITL/Util.h

@ -10,7 +10,7 @@ public: @@ -10,7 +10,7 @@ public:
Util(SITL_State *_sitlState) :
sitlState(_sitlState) {}
bool run_debug_shell(AP_HAL::BetterStream *stream) {
bool run_debug_shell(AP_HAL::BetterStream *stream) override {
return false;
}

Loading…
Cancel
Save