mirror of https://github.com/ArduPilot/ardupilot
MotorTri: check servo_out above min_throttle
This commit is contained in:
parent
f9e29a7f77
commit
385b3744ea
|
@ -141,6 +141,8 @@ void AP_MotorsTri::output_armed()
|
||||||
// check if throttle is below limit
|
// check if throttle is below limit
|
||||||
if (_rc_throttle.servo_out <= _min_throttle) {
|
if (_rc_throttle.servo_out <= _min_throttle) {
|
||||||
limit.throttle_lower = true;
|
limit.throttle_lower = true;
|
||||||
|
_rc_throttle.servo_out = _min_throttle;
|
||||||
|
_rc_throttle.calc_pwm(); // recalculate radio.out
|
||||||
}
|
}
|
||||||
//left front
|
//left front
|
||||||
motor_out[AP_MOTORS_MOT_2] = _rc_throttle.radio_out + roll_out + pitch_out;
|
motor_out[AP_MOTORS_MOT_2] = _rc_throttle.radio_out + roll_out + pitch_out;
|
||||||
|
|
Loading…
Reference in New Issue