[Solved] 3 RC Channels, and 3 Servos

Hello,
What I essentially did is used this person's idea (RCArduino: How To Read Multiple RC Channels), and a ATmega 328 to read 3 RC channels from a E-sky radio (The "information" pins are hooked up to Arduino pins 6,7,8), and pass thru this information to 3 Servos using the built-in servo library. The servos are on Arduino pins 2,3,4 and the servos are powered from a 9 volt battery.

Here's my the code with serial for debugging purposes:

#include <Servo.h> 
#include <PinChangeInt.h>


const int ch1in = 6;
volatile unsigned long ch1sS = 0;
volatile unsigned long ch1eS = 1500;
volatile boolean fch1 = false;
unsigned long ch1s = 0;
unsigned long ch1e = 1500;
unsigned long ch1m = 1500;

const int ch2in = 7;
volatile unsigned long ch2sS = 0;
volatile unsigned long ch2eS = 1500;
volatile boolean fch2 = false;
unsigned long ch2s = 0;
unsigned long ch2e = 1500;
unsigned long ch2m = 1500;

const int ch3in = 8;
volatile unsigned long ch3sS = 0;
volatile unsigned long ch3eS = 1500;
volatile boolean fch3 = false;
unsigned long ch3s = 0;
unsigned long ch3e = 1500;
unsigned long ch3m = 1500;

Servo s1;  
Servo s2;         
Servo s3; 

void setup () {
Serial.begin(9600);
PCintPort::attachInterrupt(ch1in, ch1, CHANGE);
PCintPort::attachInterrupt(ch2in, ch2, CHANGE);
PCintPort::attachInterrupt(ch3in, ch3, CHANGE);

s1.attach(2); 
s2.attach(3);
s3.attach(4);
}

void loop (){
  noInterrupts();
  ch1e = ch1eS;
  ch1s = ch1sS;

  ch2e = ch2eS;
  ch2s = ch2sS;
  
  ch3e = ch3eS;
  ch3s = ch3sS;
  interrupts();
  if (fch1 == true){
    ch1m = ch1e - ch1s;
    fch1 = false; }
    
  if (fch2 == true){
    ch2m = ch2e - ch2s;
    fch2 = false; }
    
      if (fch3 == true){
    ch3m = ch3e - ch3s;
    fch3 = false; }

    Serial.print(ch1m);
    Serial.write('    ');
    Serial.print(ch2m);
    Serial.write('    ');
    Serial.println(ch3m);
    
s1.writeMicroseconds(ch1m);
s2.writeMicroseconds(ch2m);
s3.writeMicroseconds(ch3m);
}

void ch1(){
if (digitalRead(ch1in) == HIGH) 
  ch1sS = micros();
else{
  ch1eS = micros();
  fch1 = true;}}
  
  void ch2(){
if (digitalRead(ch2in) == HIGH) 
  ch2sS = micros();
else{
  ch2eS = micros();
  fch2 = true;}}
  
    void ch3(){
if (digitalRead(ch3in) == HIGH) 
  ch3sS = micros();
else{
  ch3eS = micros();
  fch3 = true;}}

Everything works perfectly (servo's work smoothly without jitter). But as soon as I remove the serial code as in the following sketch, the servos start jittering back and froth. :~ I tried adding delays of various amount but they didn't help. It appears that the serial influences the behaviour in some way, I don't understand. Maybe someone more experienced could have insight to why it happens so.

#include <Servo.h>
#include <PinChangeInt.h>

const int ch1in = 6;
const int ch2in = 7;
const int ch3in = 8;




volatile unsigned long ch1sS = 0;
volatile unsigned long ch1eS = 1500;
volatile boolean fch1 = false;
unsigned long ch1s = 0;
unsigned long ch1e = 1500;
unsigned long ch1m = 1500;


volatile unsigned long ch2sS = 0;
volatile unsigned long ch2eS = 1500;
volatile boolean fch2 = false;
unsigned long ch2s = 0;
unsigned long ch2e = 1500;
unsigned long ch2m = 1500;

volatile unsigned long ch3sS = 0;
volatile unsigned long ch3eS = 1500;
volatile boolean fch3 = false;
unsigned long ch3s = 0;
unsigned long ch3e = 1500;
unsigned long ch3m = 1500;



Servo s1;
Servo s2;
Servo s3;

void setup () {
PCintPort::attachInterrupt(ch1in, ch1, CHANGE);
PCintPort::attachInterrupt(ch2in, ch2, CHANGE);
PCintPort::attachInterrupt(ch3in, ch3, CHANGE);

s1.attach(2);
s2.attach(3);
s3.attach(4);
}

void loop (){
  noInterrupts();
  ch1e = ch1eS;
  ch1s = ch1sS;
  
    ch2e = ch2eS;
  ch2s = ch2sS;


  ch3e = ch3eS;
  ch3s = ch3sS;


  interrupts();
if (fch1 == true){
    ch1m = ch1e - ch1s;
    fch1 = false; }
    
    if (fch2 == true){
    ch2m = ch2e - ch2s;
    fch2 = false; }
    
    if (fch3 == true){
    ch3m = ch3e - ch3s;
    fch3 = false; }

 s1.writeMicroseconds(ch1m);
 s2.writeMicroseconds(ch2m);
 s3.writeMicroseconds(ch3m);
 
 delay(20); // I have tried various amounts of delay here, and no delay at all but none seam to help
}

void ch1(){
if (digitalRead(ch1in) == HIGH) 
  ch1sS = micros();
else{
  ch1eS = micros();
  fch1 = true;}}
  
  
void ch2(){
if (digitalRead(ch2in) == HIGH) 
  ch2sS = micros();
else{
  ch2eS = micros();
  fch2 = true;}}
  
  
void ch3(){
if (digitalRead(ch3in) == HIGH) 
  ch3sS = micros();
else{
  ch3eS = micros();
  fch3 = true;}}

What kind of 9V battery? That's the most obvious potential problem, most small 9V batteries are unable to power
servos.

Its a normal 9V battery, but I don't think this is a problem because with the serial code in place everything works fine. The only thing that changes the behaviour is the presence of serial debugging code

I am afraid that I don't have anything to add to help resolve your problem, but I am interested in what the application is for controlling the servos via the Arduino having taken them from the RC receiver ?

Its a normal 9V battery, but I don't think this is a problem

I think it is a problem. Very few servos are rated for 9V.
A normal servo are usually rated for 4,8V some for 6V and a few High Voltage servos for 7,4V (two LiPo cells)

Erni is correct your servos are not rated for 9 volts they will work but failure, jitter and strange behavior will occur. The R/C device has a circuit that reduces the voltage. You will also want to check your receiver they are normally 5 volts as well. You need to get an R/C BEC that will reduce the voltage to 5 volts, battery to BEC to servos and receiver.

Ok now I'm using a 5v regulator to supply power to the servos. It works flawlessly with the sketch that includes serial debugging code. But the littering begins as soon as I remove the serial code from the sketch.

To answer your question, I'm trying to make a basic control board for a tricopter. I know i will need more then 3 chanels (at least 4 + gyroscopes) but this is to test how many chanels I can read reliably.

Well I manage all 6 on a standard Spectrum receiver as long as you have the pins you should be good.

Try with one servo do you still have jitter ?

If not add the next one in, make sure you don't have a flaky servo.

Next how do you have everything connected ? Picture or diagram would help.

Ok, I did some testing and heres what I found:

One Chanel and Servo: Serial-works, No Serial-works
Two Channels and Servos: Serial-works, No Serial-One servo jittering the other works fine
Three Channels and Servos: Serial-works, No Serial-Two servos jittering the other one works fine

Any way I've noticed that the servo that never jitters is connected to Arduino pin 2 (D2 on Atmega 328), and this is the case even if you swap the servos.
Pin 2 is not a PWM pin, but I wouldn't think this matters because servos hooked up to PWM pins jitter as well.

My current theory is that Serial capability changes the behaviour of pins 3,4 but leaves pin 2 alone. Is it even possible?

Have you tried connecting all the servos to non pwm pins ?

I will setup my servo test up later and get you the code that works for me.

No Mixing but all the servo's worked. I use a mega 2560 spectrum receiver and dx 7 TX Servos were whatever I had handy

Hi,
RCArduino is me. Servo jitter is nothing to do with PWM pins, the change in performance result from including code in the loop function or not suggests that its a timing problem.

Have you tried the original code from the blog, also how big is the jitter, is it an occasional tick which is barely enough to move the servo is it jiggling back and forth madly ?

Duane B

rcarduino.blogspot.com

Yes I can confirm that your code works perfectly on my setup both with, and without the two lines relating to serial.
Connecting all the servos to PWM/Non-PWN pins didn't solve to problem, two of the there servos are still jittering. They are wiggling with a mac deflection of about 15 degrees both ways. They do however rotate to the general angle specified by the transmitter.
I have also tried removing Serial code from the loop, but leave it in the setup function. The issue didn't go away suggesting it have something to do with printing the values to the monitor, and not with general Serial functionality.
Also, thank You, for taking your time to reply and document your findings for other people. I thought I'd never manage to thank someone who inspired be want to become an engineer

Hi,

There are a lot of differences between the original working version and yours, many of them introduce inefficiencies but the one that is causing the problem is this -

  1. You take a copy of all of the shared variables without examining the flags which tell you if they are valid.
  // blindly copy all the values available
  noInterrupts();
  ch1e = ch1eS;
  ch1s = ch1sS;

  ch2e = ch2eS;
  ch2s = ch2sS;
  
  ch3e = ch3eS;
  ch3s = ch3sS;

  // turn interrupts back on, some are going to fire immediatley meaning 
  // you have an old copy of the channel values, but are about to test new copies
  // of the channel flags
  interrupts();

At this point you have no way of knowing whether the start time and end time relate to the same pulse, or if you have an end time for the last pulse but a start time for a new pulse that has not ended yet.

  1. You then examing the flags to see if they are valid and then perform some calculation.
 // Here your testing a live copy of the flag but then calculating based on 
 // old copies of the channel values
 if (fch1 == true){
    ch1m = ch1e - ch1s;
    fch1 = false; }
    
 if (fch2 == true){
    ch2m = ch2e - ch2s;
    fch2 = false; }
    
 if (fch3 == true){
    ch3m = ch3e - ch3s;
    fch3 = false; }

You might be thinking that the fchn flag will tell you if a pulse is complete i.e. you have the start time and end time for the same pulse, but it does not. When you copied the variables in 1) above, you turned interrupts off. You then took a few microseconds to copy the channel values before turning interrupts back on. During this time, interrupts will be getting queued up ready to fire as soon as they are turned back on.

The next thing you do is test the fchn flags to see if you have the start and end of a pulse - but the problem is between you taking the local copies of the start and end, some interrupts will have fired and updated the fchn flag so you have a current copy of the flag, but an old and invalid copy of the start and end times.

This also explains why one servo ch1 performs better than the others, there is less time between you taking the local copies of its values and testing its flags so less opportunity for fch1 to get updated.

As for the effect of serial, thats just the way it is with timing problems, they often make it appear that the problem is somewhere unrelated.

There are lots of ways for you to fix this, see if you can figure any out and let us know, also when you are ready to stretch a bit further, try this more advanced approach -

Duane B

rcarduino.blogspot.com

Yes, what you suggested did the trick. I have also changed the boolean variables into a single bit variable, as I suspect access might be quicker.
Here's my modified code:

#include <Servo.h>
#include <PinChangeInt.h>

#define ch1in  6
#define ch2in  7
#define ch3in  8

#define sv1ot 0
#define sv2ot 1
#define sv3ot 3

#define ch1f B00000001
#define ch2f B00000010
#define ch3f B00000100

#define ich1f B11111110
#define ich2f B11111101
#define ich3f B11111011

volatile unsigned long ch1sS = 0;
volatile unsigned long ch1eS = 1500;
unsigned long ch1s = 0;
unsigned long ch1e = 1500;
unsigned long ch1m = 1500;


volatile unsigned long ch2sS = 0;
volatile unsigned long ch2eS = 1500;
unsigned long ch2s = 0;
unsigned long ch2e = 1500;
unsigned long ch2m = 1500;

volatile unsigned long ch3sS = 0;
volatile unsigned long ch3eS = 1500;
unsigned long ch3s = 0;
unsigned long ch3e = 1500;
unsigned long ch3m = 1500;

volatile uint8_t flags;


Servo s1;
Servo s2;
Servo s3;

void setup () {
  
  
PCintPort::attachInterrupt(ch1in, ch1, CHANGE);
PCintPort::attachInterrupt(ch2in, ch2, CHANGE);
PCintPort::attachInterrupt(ch3in, ch3, CHANGE);

s1.attach(sv1ot);
s2.attach(sv2ot);
s3.attach(sv3ot);
}

void loop (){
  
  if(flags){
  noInterrupts();
  
  
  if(flags & ch1f){
  ch1e = ch1eS;
  ch1s = ch1sS;
  flags &= ich1f;
  }
  
  if(flags & ch2f){
  ch2e = ch2eS;
  ch2s = ch2sS;
  flags &= ich2f;
  }
  
  
if(flags & ch3f){
  ch3e = ch3eS;
  ch3s = ch3sS;
  flags &= ich3f;
  
}

  
  interrupts();
  }
  
    ch1m = ch1e - ch1s;
    ch2m = ch2e - ch2s;
    ch3m = ch3e - ch3s;


 s1.writeMicroseconds(ch1m);
 s2.writeMicroseconds(ch2m);
 s3.writeMicroseconds(ch3m);
 
}

void ch1(){
if (digitalRead(ch1in) == HIGH) 
  ch1sS = micros();
else{
  ch1eS = micros();
  flags |= ch1f;}}
  
  
void ch2(){
if (digitalRead(ch2in) == HIGH) 
  ch2sS = micros();
else{
  ch2eS = micros();
  flags |= ch2f;}}
  
  
void ch3(){
if (digitalRead(ch3in) == HIGH)
  ch3sS = micros();
else{
  ch3eS = micros();
  flags |= ch3f;}}

I'll be tying to replace digitalRead in the ISR to direct access to the registers.

And again thank you to everyone who responded, and helped to fix the problem.