1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Fix tri_unarmed_servo (was broken by pid_at_min_throttle changes)

This commit is contained in:
Nicholas Sherlock 2015-04-19 08:08:37 +12:00
parent ebd5475a55
commit 08efc2e66d

View file

@ -702,7 +702,9 @@ void loop(void)
// If we're armed, at minimum throttle, and we do arming via the
// sticks, do not process yaw input from the rx. We do this so the
// motors do not spin up while we are trying to arm or disarm.
if (isUsingSticksForArming() && rcData[THROTTLE] <= masterConfig.rxConfig.mincheck) {
// Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
if (isUsingSticksForArming() && rcData[THROTTLE] <= masterConfig.rxConfig.mincheck
&& !(masterConfig.mixerMode == MIXER_TRI && masterConfig.mixerConfig.tri_unarmed_servo)) {
rcCommand[YAW] = 0;
}