MotorsTri: add 80% throttle limit
This limit was moved from the main copter flight code to the motors library in order that the throttle_upper flag could be set properly.
This commit is contained in:
parent
8754ce9eed
commit
3550e52560
@ -108,6 +108,13 @@ void AP_MotorsTri::output_armed()
|
||||
limit.throttle_upper = true;
|
||||
}
|
||||
|
||||
// tricopters limit throttle to 80%
|
||||
// To-Do: implement improved stability patch and remove this limit
|
||||
if (_rc_throttle.servo_out > 800) {
|
||||
_rc_throttle.servo_out = 800;
|
||||
limit.throttle_upper = true;
|
||||
}
|
||||
|
||||
// capture desired roll, pitch, yaw and throttle from receiver
|
||||
_rc_roll.calc_pwm();
|
||||
_rc_pitch.calc_pwm();
|
||||
|
Loading…
Reference in New Issue
Block a user