mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Copter: move 80% thr limit to MotorsTri
This commit is contained in:
parent
43ba94e99a
commit
8754ce9eed
@ -694,10 +694,6 @@ set_servos_4()
|
||||
if (ap.motor_test) {
|
||||
motor_test_output();
|
||||
} else {
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
// To-Do: implement improved stability patch for tri so that we do not need to limit throttle input to motors
|
||||
g.rc_3.servo_out = min(g.rc_3.servo_out, 800);
|
||||
#endif
|
||||
motors.output();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user