diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 6795747b1c..242d50bf60 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -568,7 +568,7 @@ void PX4RCOutput::push() } } -void PX4RCOutput::_timer_tick(void) +void PX4RCOutput::timer_tick(void) { if (_output_mode != MODE_PWM_ONESHOT && !_corking) { /* in oneshot mode the timer does nothing as the outputs are diff --git a/libraries/AP_HAL_PX4/RCOutput.h b/libraries/AP_HAL_PX4/RCOutput.h index 5c6eddbf09..717da8e88a 100644 --- a/libraries/AP_HAL_PX4/RCOutput.h +++ b/libraries/AP_HAL_PX4/RCOutput.h @@ -33,8 +33,8 @@ public: void push(); void set_output_mode(enum output_mode mode) override; - - void _timer_tick(void); + + void timer_tick(void) override; bool enable_sbus_out(uint16_t rate_hz) override; private: diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index 3d386f3265..3979604bfc 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -280,7 +280,7 @@ void *PX4Scheduler::_timer_thread(void *arg) perf_end(sched->_perf_timers); // process any pending RC output requests - ((PX4RCOutput *)hal.rcout)->_timer_tick(); + hal.rcout->timer_tick(); // process any pending RC input requests ((PX4RCInput *)hal.rcin)->_timer_tick();