mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
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:
parent
a5bafb399f
commit
5179d13dbf
@ -66,4 +66,10 @@ public:
|
|||||||
timeout
|
timeout
|
||||||
*/
|
*/
|
||||||
virtual bool wait_timeout(uint16_t n, uint32_t timeout_ms) { return false; }
|
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) { }
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user