From e05de48e2d059759314588bd25970c3a6ec91d25 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Thu, 8 Sep 2011 04:58:42 +0000 Subject: [PATCH] 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 --- libraries/RC_Channel/RC_Channel.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 677f928531..24fae0f5ea 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -80,7 +80,7 @@ RC_Channel::set_pwm(int pwm) if(radio_in == 0) radio_in = pwm; else - radio_in = ((pwm + radio_in) >> 1); // Small filtering + radio_in = (pwm + radio_in) >> 1; // Small filtering }else{ radio_in = pwm; } @@ -124,7 +124,7 @@ RC_Channel::calc_pwm(void) }else if(_type == RC_CHANNEL_ANGLE_RAW){ pwm_out = (float)servo_out * .1; - radio_out = pwm_out + 1500; + radio_out = (pwm_out * _reverse) + 1500; }else{ pwm_out = angle_to_pwm();