mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
SRV_Channel: adjust trim, check all channels for range limit
This commit is contained in:
parent
fa8072de6c
commit
16b8071f6d
@ -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) {
|
} else if (change < 0 && trim_scaled > 0.4f) {
|
||||||
new_trim--;
|
new_trim--;
|
||||||
} else {
|
} else {
|
||||||
return;
|
continue;
|
||||||
}
|
}
|
||||||
c.servo_trim.set(new_trim);
|
c.servo_trim.set(new_trim);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user