mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added set_reversible_mask()
This commit is contained in:
parent
1910f266a6
commit
f2cd6e9a05
|
@ -50,6 +50,13 @@ public:
|
|||
*/
|
||||
virtual void write(uint8_t chan, uint16_t period_us) = 0;
|
||||
|
||||
/*
|
||||
* mark the channels in chanmask as reversible. This is needed for some ESC types (such as DShot)
|
||||
* so that output scaling can be performed correctly. The chanmask passed is added (ORed) into
|
||||
* any existing mask.
|
||||
*/
|
||||
virtual void set_reversible_mask(uint16_t chanmask) {}
|
||||
|
||||
/*
|
||||
* Delay subsequent calls to write() going to the underlying hardware in
|
||||
* order to group related writes together. When all the needed writes are
|
||||
|
|
Loading…
Reference in New Issue