mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Fix RC range reversal
This commit is contained in:
parent
2fa92aea4c
commit
9f14c5f578
@ -121,7 +121,7 @@ RC_Channel::calc_pwm(void)
|
|||||||
{
|
{
|
||||||
if(_type == RC_CHANNEL_RANGE){
|
if(_type == RC_CHANNEL_RANGE){
|
||||||
pwm_out = range_to_pwm();
|
pwm_out = range_to_pwm();
|
||||||
radio_out = pwm_out + radio_min;
|
radio_out = (_reverse >=0 ? pwm_out + radio_min : radio_max - pwm_out);
|
||||||
|
|
||||||
}else if(_type == RC_CHANNEL_ANGLE_RAW){
|
}else if(_type == RC_CHANNEL_ANGLE_RAW){
|
||||||
pwm_out = (float)servo_out * .1;
|
pwm_out = (float)servo_out * .1;
|
||||||
|
Loading…
Reference in New Issue
Block a user