Adding reverse to Channel Raw output (unscaled output) to fix camera reversing.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3297 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-09-08 04:58:42 +00:00
parent 3b622dc43c
commit e05de48e2d

View File

@ -80,7 +80,7 @@ RC_Channel::set_pwm(int pwm)
if(radio_in == 0) if(radio_in == 0)
radio_in = pwm; radio_in = pwm;
else else
radio_in = ((pwm + radio_in) >> 1); // Small filtering radio_in = (pwm + radio_in) >> 1; // Small filtering
}else{ }else{
radio_in = pwm; radio_in = pwm;
} }
@ -124,7 +124,7 @@ RC_Channel::calc_pwm(void)
}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;
radio_out = pwm_out + 1500; radio_out = (pwm_out * _reverse) + 1500;
}else{ }else{
pwm_out = angle_to_pwm(); pwm_out = angle_to_pwm();