mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: add constraint to move_servo
This commit is contained in:
parent
eea7459c3c
commit
36bcabb4e4
@ -340,6 +340,7 @@ SRV_Channels::move_servo(SRV_Channel::Aux_servo_function_t function,
|
||||
return;
|
||||
}
|
||||
float v = float(value - angle_min) / float(angle_max - angle_min);
|
||||
v = constrain_float(v, 0.0f, 1.0f);
|
||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||
SRV_Channel &ch = channels[i];
|
||||
if (ch.function.get() == function) {
|
||||
|
Loading…
Reference in New Issue
Block a user