mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: add accessor for reversed mask
allow mask updates to be disabled document mask types define DSHOT_ZERO_THROTTLE
This commit is contained in:
parent
5ece42bce0
commit
09e0135ecb
|
@ -52,22 +52,30 @@ public:
|
|||
|
||||
/*
|
||||
* 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.
|
||||
* so that output scaling can be performed correctly. The chanmask passed is added (ORed) into any existing mask.
|
||||
* The mask uses servo channel numbering
|
||||
*/
|
||||
virtual void set_reversible_mask(uint16_t chanmask) {}
|
||||
|
||||
/*
|
||||
* mark the channels in chanmask as reversed. The chanmask passed is added (ORed) into
|
||||
* any existing mask.
|
||||
* mark the channels in chanmask as reversed.
|
||||
* The chanmask passed is added (ORed) into any existing mask.
|
||||
* The mask uses servo channel numbering
|
||||
*/
|
||||
virtual void set_reversed_mask(uint16_t chanmask) {}
|
||||
virtual uint16_t get_reversed_mask() { return 0; }
|
||||
|
||||
/*
|
||||
* Update channel masks at 1Hz allowing for actions such as dshot commands to be sent
|
||||
*/
|
||||
virtual void update_channel_masks() {}
|
||||
|
||||
/*
|
||||
* Allow channel mask updates to be temporarily suspended
|
||||
*/
|
||||
virtual void disable_channel_mask_updates() {}
|
||||
virtual void enable_channel_mask_updates() {}
|
||||
|
||||
/*
|
||||
* Delay subsequent calls to write() going to the underlying hardware in
|
||||
* order to group related writes together. When all the needed writes are
|
||||
|
@ -225,6 +233,8 @@ public:
|
|||
DSHOT_LED3_OFF = 29,
|
||||
};
|
||||
|
||||
const uint8_t DSHOT_ZERO_THROTTLE = 48;
|
||||
|
||||
enum DshotEscType {
|
||||
DSHOT_ESC_NONE = 0,
|
||||
DSHOT_ESC_BLHELI = 1
|
||||
|
|
Loading…
Reference in New Issue