AP_HAL: added virtual _timer_tick method on UARTDriver

this is needed to allow HALs to update UARTs when the number of UARTs
they bhave varies (some may be instances of HAL_Empty)
This commit is contained in:
Andrew Tridgell 2018-01-22 06:44:53 +11:00
parent a5bafb399f
commit 5179d13dbf

View File

@ -66,4 +66,10 @@ public:
timeout
*/
virtual bool wait_timeout(uint16_t n, uint32_t timeout_ms) { 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) { }
};