Skip to content
Snippets Groups Projects
Commit 2cc9fde3 authored by Jason Short's avatar Jason Short
Browse files

removed never used filter, and fixed a constrain that could make range calcs go bad

parent 00cabc63
No related branches found
No related tags found
No related merge requests found
......@@ -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 ");
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment