SRV_Channel: adjust trim, check all channels for range limit

This commit is contained in:
Iampete1 2022-09-16 21:56:43 +01:00 committed by Randy Mackay
parent cd3b7389ea
commit 1d9fb68036

View File

@ -684,7 +684,7 @@ void SRV_Channels::adjust_trim(SRV_Channel::Aux_servo_function_t function, float
} else if (change < 0 && trim_scaled > 0.4f) {
new_trim--;
} else {
return;
continue;
}
c.servo_trim.set(new_trim);