mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
TradHeli: implement get_motor_mask
This commit is contained in:
parent
6d99524e56
commit
72c3e9cc72
@ -363,6 +363,14 @@ void AP_MotorsHeli::recalc_scalers()
|
||||
_rsc_runup_increment = 1000.0f / (_rsc_runup_time * 100.0f);
|
||||
}
|
||||
|
||||
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (1 means being used)
|
||||
// this can be used to ensure other pwm outputs (i.e. for servos) do not conflict
|
||||
uint16_t AP_MotorsHeli::get_motor_mask()
|
||||
{
|
||||
// heli uses channels 1,2,3,4,7 and 8
|
||||
return (1U << 0 | 1U << 1 | 1U << 2 | 1U << 3 | 1U << AP_MOTORS_HELI_AUX | 1U << AP_MOTORS_HELI_RSC);
|
||||
}
|
||||
|
||||
//
|
||||
// protected methods
|
||||
//
|
||||
@ -797,4 +805,4 @@ void AP_MotorsHeli::set_delta_phase_angle(int16_t angle)
|
||||
angle = constrain_int16(angle, -90, 90);
|
||||
_delta_phase_angle = angle;
|
||||
calculate_roll_pitch_collective_factors();
|
||||
}
|
||||
}
|
||||
|
@ -199,6 +199,10 @@ public:
|
||||
// recalculation of collective factors
|
||||
void set_delta_phase_angle(int16_t angle);
|
||||
|
||||
// get_motor_mask - returns a bitmask of which outputs are being used for motors or servos (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();
|
||||
|
||||
protected:
|
||||
|
||||
// output - sends commands to the motors
|
||||
|
Loading…
Reference in New Issue
Block a user