mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_HAL: RCOutput: add optional timer_tick() method
This is common enough across the HAL implementaions so add a method for it to avoid the need for casts inside the HALs.
This commit is contained in:
parent
a589a84e32
commit
686e0f08d6
@ -112,7 +112,13 @@ public:
|
||||
enable SBUS out at the given rate
|
||||
*/
|
||||
virtual bool enable_sbus_out(uint16_t rate_gz) { return false; }
|
||||
|
||||
|
||||
/*
|
||||
* Optional method to control the update of the motors. Derived classes
|
||||
* can implement it if their HAL layer requires.
|
||||
*/
|
||||
virtual void timer_tick(void) { }
|
||||
|
||||
/*
|
||||
output modes. Allows for support of oneshot
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user