mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_HAL: allow forcing of trigger_groups()
This commit is contained in:
parent
6ac35ce9af
commit
c4ab8e25c4
@ -376,6 +376,11 @@ public:
|
|||||||
*/
|
*/
|
||||||
virtual void write_gpio(uint8_t chan, bool active) {};
|
virtual void write_gpio(uint8_t chan, bool active) {};
|
||||||
|
|
||||||
|
/*
|
||||||
|
Force group trigger from all callers rather than just from the main thread
|
||||||
|
*/
|
||||||
|
virtual void force_trigger_groups(bool onoff) {};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* calculate the prescaler required to achieve the desire bitrate
|
* calculate the prescaler required to achieve the desire bitrate
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user