Motor Encoders with Arduino

If Colin is going to create a map of the space he’s in, he needs to be able to find the distance between objects in the space. If he’s going to accurately control his own motion, he needs to be able to control the speed of his motors. For both of these things he needs information about how far and how fast his motors are turning. To give Colin that information I added encoders to his motors. Encoders are special sensors that track both how far his motor shafts have turned, and in what direction.

The following tutorial will discuss how to use shaft encoders with DC motors. First I’ll discuss the principles the encoders work on, then I’ll show you how to wire up an encoder and verify that it’s working. This tutorial owes a large dept to the Penn State Robotics Club Wiki, which has an excellent page on wheel encoders.

For this tutorial I’ll be using these magnetic encoders from Pololu. They are great for use with an Arduino because their output is a nice, easy to read, digital square wave. Pololu also offers an analog optical encoder, but to reliably read its output you need to use a ADC (analog to digital converter). Also, the optical encoder is susceptible to interference from bright light. So magnetic encoders are easier to use and more reliable for our purposes.


Encoder Principles

Pololu’s shaft encoders add a 6 pole magnetic disc to the shaft of the motor, as well as two Hall effect sensors. As the motor turns the disc rotates past the sensors. Each time a magnetic pole passes a sensor, the encoder outputs a digital pulse, also called a “tick.” The encoder setup is pictured below.

motor encoder installation

motor encoder installation example (from pololu.com)

The encoder has two outputs, one for each Hall effect sensor. The sensors are separated by 90 degrees. This means the square wave outputs of the sensors are 90 degrees out of phase. This is called a quadrature output. The picture below (taken from Pololu’s website) shows the typical output of an encoder.

encoder output

Output of an encoder (from pololu.com)

Why is it important that the output pulses are 90 degrees out of phase? This allows us to determine both the magnitude and the direction of the motor’s rotation. If output A is ahead of output B, then the motor is turning forward. If output A is behind B, the motor is turning backward. Pretty cool, right?


Encoder Setup and Wiring

Wiring up the encoders is pretty simple. See the diagram below for details on wiring up the encoder for motor B, and repeat for motor A.

wiring for a single motor and encoder

wiring for a single motor and encoder

Note that the encoder pin OUTA needs to be connected to a hardware interrupt pin (digital pin 2 or 3 on an Arduino Duemilanove or Uno). For this example it’s not really necessary to use hardware interrupts but if you don’t your Arduino won’t be able to do anything but track the encoder. Interrupts allow your Arduino to keep track of the encoders while it’s running another program.

It’s also important when installing your motors to not mount them too close to each other. If your motors are mounted back-to-back, the magnetic encoder wheels will interfere with each other. I initially had only about 5mm between the two encoder wheels. The magnets in the encoder wheels linked with each other and made it impossible for the two motors to turn at different speeds. Keeping the encoder wheels at least 20mm apart seems to avoid any interference problems.


Hardware Interrupts

It’s pretty easy to write a program that simply counts the number of ticks. But if, for some reason, you want your program to do anything but track the encoders you need to use hardware interrupts.

With hardware interrupts your main program runs until the state of one of the Arduino’s interrupt pins changes. Then the main program is stopped, a special interrupt method is run, then the main program is resumed. For example, an obstacle avoidance routine can run in the foreground but if one of the interrupt pins changes from low to high the position or speed of the motor can be updated in the interrupt method.

Because the main program is stopped when the interrupt method is triggered, the length of the interrupt method should be kept as short as possible. If the interrupt method is too long, then the Arduino will spend all of its time running the interrupt method and it will never actually run the main program.

For more details on hardware interrupts check out this page on the Arduino playground.


Example Sketch

The sketch below simply prints the values of the two count variables. When the motors are moved, the encoder output triggers the appropriate encoder event method. The encoder event methods either increment or decrement the count variables, keeping track of the number of ticks from each encoder. If the motor is turned forward, the count is incremented and it is decremented if the motor is turned backward.

The motors need to be moved manually for this sketch. They won’t move themselves. We will expand this to do simple motor speed control in a later tutorial.

We’ll define motor direction somewhat arbitrarily: If RH_ENCODER_A is HIGH and RH_ENCODER_B is LOW then the motor is turning forward. If RH_ENCODER_A is HIGH and RH_ENCODER_B is also HIGH, then the motor is turning backward. You can swap the wires for ENCODER_A and ENCODER_B to change the direction if required.

/*
 * Encoder example sketch
 * by Andrew Kramer
 * 1/1/2016
 *
 * Records encoder ticks for each wheel
 * and prints the number of ticks for
 * each encoder every 500ms
 *
 */

// pins for the encoder inputs
#define RH_ENCODER_A 3 
#define RH_ENCODER_B 5
#define LH_ENCODER_A 2
#define LH_ENCODER_B 4

// variables to store the number of encoder pulses
// for each motor
volatile unsigned long leftCount = 0;
volatile unsigned long rightCount = 0;

void setup() {
  pinMode(LH_ENCODER_A, INPUT);
  pinMode(LH_ENCODER_B, INPUT);
  pinMode(RH_ENCODER_A, INPUT);
  pinMode(RH_ENCODER_B, INPUT);
  
  // initialize hardware interrupts
  attachInterrupt(0, leftEncoderEvent, CHANGE);
  attachInterrupt(1, rightEncoderEvent, CHANGE);
  
  Serial.begin(9600);
}

void loop() {
  Serial.print("Right Count: ");
  Serial.println(rightCount);
  Serial.print("Left Count: ");
  Serial.println(leftCount);
  Serial.println();
  delay(500);
}

// encoder event for the interrupt call
void leftEncoderEvent() {
  if (digitalRead(LH_ENCODER_A) == HIGH) {
    if (digitalRead(LH_ENCODER_B) == LOW) {
      leftCount++;
    } else {
      leftCount--;
    }
  } else {
    if (digitalRead(LH_ENCODER_B) == LOW) {
      leftCount--;
    } else {
      leftCount++;
    }
  }
}

// encoder event for the interrupt call
void rightEncoderEvent() {
  if (digitalRead(RH_ENCODER_A) == HIGH) {
    if (digitalRead(RH_ENCODER_B) == LOW) {
      rightCount++;
    } else {
      rightCount--;
    }
  } else {
    if (digitalRead(RH_ENCODER_B) == LOW) {
      rightCount--;
    } else {
      rightCount++;
    }
  }
}

That’s all for today. In my next post I’ll take what we learned about using encoders with hardware interrupts and incorporate that into a simple speed control routine. After that we can dive into real PID control!