mirror of https://github.com/ArduPilot/ardupilot
removed never used filter, and fixed a constrain that could make range calcs go bad
This commit is contained in:
parent
00cabc6343
commit
2cc9fde3c9
|
@ -96,14 +96,16 @@ RC_Channel::set_pwm(int pwm)
|
||||||
{
|
{
|
||||||
//Serial.print(pwm,DEC);
|
//Serial.print(pwm,DEC);
|
||||||
|
|
||||||
if(_filter){
|
/*if(_filter){
|
||||||
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;
|
||||||
}
|
}*/
|
||||||
|
|
||||||
|
radio_in = constrain(pwm, radio_min.get(), radio_max.get());
|
||||||
|
|
||||||
if(_type == RC_CHANNEL_RANGE){
|
if(_type == RC_CHANNEL_RANGE){
|
||||||
//Serial.print("range ");
|
//Serial.print("range ");
|
||||||
|
|
Loading…
Reference in New Issue