mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
AP_MotorsHeli: Colyaw function to check if rotor speed control is above idle
This commit is contained in:
parent
d788f0307d
commit
9e8f5a42f4
@ -496,9 +496,9 @@ void AP_MotorsHeli_Single::move_swash(int16_t roll_out, int16_t pitch_out, int16
|
|||||||
coll_out_scaled = _collective_out * _collective_scalar + _collective_min - 1000;
|
coll_out_scaled = _collective_out * _collective_scalar + _collective_min - 1000;
|
||||||
|
|
||||||
// rudder feed forward based on collective
|
// rudder feed forward based on collective
|
||||||
// the feed-forward is not required when the motor is shut down and not creating torque
|
// the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque
|
||||||
// also not required if we are using external gyro
|
// also not required if we are using external gyro
|
||||||
if ((_main_rotor.get_control_speed() > 0) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
if ((_main_rotor.get_control_speed() > _rsc_idle) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) {
|
||||||
// sanity check collective_yaw_effect
|
// sanity check collective_yaw_effect
|
||||||
_collective_yaw_effect = constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE);
|
_collective_yaw_effect = constrain_float(_collective_yaw_effect, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE);
|
||||||
yaw_offset = _collective_yaw_effect * abs(_collective_out - _collective_mid_pwm);
|
yaw_offset = _collective_yaw_effect * abs(_collective_out - _collective_mid_pwm);
|
||||||
|
Loading…
Reference in New Issue
Block a user