mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
Motors: add get_motor_mask method
This returns a bitmask of output channels that are used by the motors library. This allows removing the chance of a do-set-servo interfering with a motor or control surface used to control the vehicle.
This commit is contained in:
parent
1ea1d9983d
commit
7749bfe82c
@ -130,6 +130,10 @@ public:
|
||||
// Note: this must be set immediately before a step up in throttle
|
||||
void slow_start(bool true_false);
|
||||
|
||||
// get_motor_mask - returns a bitmask of which outputs are being used for motors (1 means being used)
|
||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
virtual uint16_t get_motor_mask() = 0;
|
||||
|
||||
// structure for holding motor limit flags
|
||||
struct AP_Motors_limit {
|
||||
uint8_t roll_pitch : 1; // we have reached roll or pitch limit
|
||||
|
Loading…
Reference in New Issue
Block a user