mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: apply tailsitter min spin to both motors
This commit is contained in:
parent
e5154abc38
commit
98c2f23371
|
@ -75,8 +75,8 @@ void AP_MotorsTailsitter::output_to_motors()
|
||||||
case THROTTLE_UNLIMITED:
|
case THROTTLE_UNLIMITED:
|
||||||
case SPOOL_DOWN: {
|
case SPOOL_DOWN: {
|
||||||
throttle = _spin_min + throttle * (1 - _spin_min);
|
throttle = _spin_min + throttle * (1 - _spin_min);
|
||||||
throttle_left = constrain_float(throttle + _rudder*0.5, 0, 1);
|
throttle_left = constrain_float(throttle + _rudder*0.5, _spin_min, 1);
|
||||||
throttle_right = constrain_float(throttle - _rudder*0.5, 0, 1);
|
throttle_right = constrain_float(throttle - _rudder*0.5, _spin_min, 1);
|
||||||
// initialize limits flags
|
// initialize limits flags
|
||||||
limit.roll_pitch = false;
|
limit.roll_pitch = false;
|
||||||
limit.yaw = false;
|
limit.yaw = false;
|
||||||
|
|
Loading…
Reference in New Issue