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:
Lucas De Marchi 2017-02-07 19:45:50 -08:00 committed by Andrew Tridgell
parent a589a84e32
commit 686e0f08d6

View File

@ -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
*/