mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_PX4: rename method to follow AP_HAL
This allows to avoid the cast in the HAL, making it easier to replace the implementation with an Empty::RCOutput while prototyping.
This commit is contained in:
parent
686e0f08d6
commit
f972fed70b
|
@ -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
|
||||
|
|
|
@ -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:
|
||||
|
|
|
@ -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();
|
||||
|
|
Loading…
Reference in New Issue