From 2cc9fde3c930f1c67a17552107173b2dea6ef1b8 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 31 May 2012 11:45:07 -0700 Subject: [PATCH] removed never used filter, and fixed a constrain that could make range calcs go bad --- libraries/RC_Channel/RC_Channel.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 51aaf68e81..93eae4751c 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -96,14 +96,16 @@ RC_Channel::set_pwm(int pwm) { //Serial.print(pwm,DEC); - if(_filter){ + /*if(_filter){ if(radio_in == 0) radio_in = pwm; else radio_in = (pwm + radio_in) >> 1; // Small filtering }else{ radio_in = pwm; - } + }*/ + + radio_in = constrain(pwm, radio_min.get(), radio_max.get()); if(_type == RC_CHANNEL_RANGE){ //Serial.print("range ");