mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
SRV_Channel: pwm_from_angle: return trim for 0 high_out
This commit is contained in:
parent
623501d0d5
commit
5382083452
@ -99,6 +99,9 @@ uint16_t SRV_Channel::pwm_from_range(float scaled_value) const
|
||||
// convert a -angle_max..angle_max to a pwm
|
||||
uint16_t SRV_Channel::pwm_from_angle(float scaled_value) const
|
||||
{
|
||||
if (high_out == 0) {
|
||||
return servo_trim;
|
||||
}
|
||||
if (reversed) {
|
||||
scaled_value = -scaled_value;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user