arduinosignal-processinginterruptroboticsinterrupt-handling

How to remove noise from PWM read from a radio receiver?


I am using a Remote Control from FlySky. For my robotics project, I want to read PWM from the receiver on an Arduino. I came across 2 options:

I cant use the first option of pulseIn() because I want my robot to continue with the operation if receiver signal are not coming (Tx not available etc.) So I used ISR.

Most reliable source : Mr. Brookings channel on YouTube.

Here is what I did (Only the required part for 1 axis):

// [R] where R is defined as 0 => [R] == [0]

volatile long CH[4];   //4 pwms to read so array of 4
float IN[3]={0,0,0};   // throttle is directly written
unsigned long timer[4],curr_time; 
byte last[4];   

void setup(){
    PCICR |= (1 << PCIE0);  
    PCMSK0 |= (1 << PCINT0);
    PCMSK0 |= (1 << PCINT1);
    PCMSK0 |= (1 << PCINT2);
    PCMSK0 |= (1 << PCINT3);

    /* There is some more code here */

    
    Serial.begin(115200);
}
void loop(){

    /* There is some more code here */
    IN[R] = ((CH[ROLL]  - (1500 + R_TRIM))/11.0);  // eg.: (1200 - (1500 + 8))/11.0 = -28 (interpreted as setpoint of -28° by the robot) 
    Serial.println(IN[R]);
}

ISR(PCINT0_vect){

    curr_time = micros();
    //channel 1 roll
    if(PINB & B00000001){
        if(last[ROLL] == 0){
            last[ROLL] = 1;
            timer[ROLL] = curr_time;
        }
    }
    else if(last[ROLL] == 1){
        last[ROLL] = 0;
        CH[ROLL] = ((curr_time - timer[ROLL]));
    }
}

I can read the PWM actually, but the robot keeps showing random twitches in its control at a given set point. I managed to trace the reason and found out that the PWM is insanely ridden by noise. Its not stable like it should be - steady. I have a MATLAB plot I used for analysis:

Signal (IN[R]): RC pwm read

Close up (when Tx stick was in the middle w/o movement) : Closeup signal

There are such spikes coming which is adding up to the control signal eventually making my robot to twitch. I tried some filtering techniques like 'moving average' and '1st and 2nd order exponential filters'. Also checked if it was due to power supplied to it - tried putting a capacitor or an iron core to the power lines but in vain. I can figure out how to remove them as their some constrains :

I would appreciate some guidance!


Solution

  • There's no way of telling from this if the input is noisy, or if your code is reading the PWM wrong, of if something else is going on, like external noise on the line, the Arduino's clock jitter, or other interrupts taking time. Also note that micros() on an Arduino Uno only has a resolution of 4µs, not 1µs.

    You should check the input for jitter and noise, and try fast code that isn't influenced by other interrupts.

    A fairly simple and fast way of getting the PWM pulse width is something like this, preferably without using anything else that uses interrupts:

    volatile int pwmPulseWidth = 0;
    volatile unsigned long int previousTime = 0;
     
    void setup() {
      attachInterrupt(0, rising, RISING);
    }
     
    void loop() {
      // pwmPulseWidth is available here.
    }
     
    void rising() {
      attachInterrupt(0, falling, FALLING);
      previousTime = micros();
    }
     
    void falling() {
      attachInterrupt(0, rising, RISING);
      pwmPulseWidth = micros() - previousTime;
    }
    

    Untested, but it should give you an idea. This will return the width of the PWM pulse.

    There are other ways of doing this, of course, like using a timer in capture mode.

    Knowing the PWM frequency and the width of the PWM pulse is enough to reconstruct the PWM signal, should you want to.