How to Calculate the Velocity of a DC Motor With Encoder

In this tutorial, we learn how to calculate the angular velocity (magnitude and direction of rotation in radians per second) of a DC motor with a built-in encoder.  

Here is the motor we will work with, but you can use any motor that looks like this one.

1_dc_motor_encoder_wheels-1

Real-World Applications

Knowing the angular velocity of wheels on a robot helps us calculate how fast the robot is moving (i.e. speed) as well as the distance a robot has traveled in a given unit of time. This information is important for helping us determine where a robot is in a particular environment (i.e. odometry).

Prerequisites

You Will Need

This section is the complete list of components you will need for this project (#ad).

2 x JGB37-520B DC Motor with Encoder OR 2 x JGB37-520B DC 6V 12V Micro Geared Motor With Encoder and Wheel Kit (includes wheels)

Arduino Uno r3

OR

Self-Balancing Car Kit (which includes everything above and more…Elegoo and Osoyoo are good brands you can find on Amazon.com)

Disclosure (#ad): As an Amazon Associate I earn from qualifying purchases.

Set Up the Hardware

The first thing we need to do is set up the hardware.

Here is the wiring diagram:

jgb37_dc_motor_with_encoder-2
  • The Ground pin of the motor connects to GND of the Arduino.
  • Encoder A (sometimes labeled C1) of the motor connects to pin 2 of the Arduino. Pin 2 of the Arduino will record every time there is a rising digital signal from Encoder A.
  • Encoder B (sometimes labeled C2) of the motor connects to pin 4 of the Arduino. The signal that is read off pin 4 on the Arduino will determine if the motor is moving forward or in reverse.
  • The VCC pin of the motor connects to the 5V pin of the Arduino. This pin is responsible for providing power to the encoder.
  • For this project, you don’t need to connect the motor pins (+ and – terminals) to anything since you will be turning the motor manually with your hand. 

Write and Load the Code to Calculate Angular Velocity

Now we’re ready to calculate the angular velocity of the wheel. 

Open the Arduino IDE, and write the following program. The name of my program is calculate_angular_velocity.ino.

/*
 * Author: Automatic Addison
 * Website: https://automaticaddison.com
 * Description: Calculate the angular velocity in radians/second of a DC motor
 * with a built-in encoder (forward = positive; reverse = negative) 
 */

// Motor encoder output pulses per 360 degree revolution (measured manually)
#define ENC_COUNT_REV 620

// Encoder output to Arduino Interrupt pin. Tracks the pulse count.
#define ENC_IN_RIGHT_A 2

// Other encoder output to Arduino to keep track of wheel direction
// Tracks the direction of rotation.
#define ENC_IN_RIGHT_B 4

// True = Forward; False = Reverse
boolean Direction_right = true;

// Keep track of the number of right wheel pulses
volatile long right_wheel_pulse_count = 0;

// One-second interval for measurements
int interval = 1000;
 
// Counters for milliseconds during interval
long previousMillis = 0;
long currentMillis = 0;

// Variable for RPM measuerment
float rpm_right = 0;

// Variable for angular velocity measurement
float ang_velocity_right = 0;
float ang_velocity_right_deg = 0;

const float rpm_to_radians = 0.10471975512;
const float rad_to_deg = 57.29578;

void setup() {

  // Open the serial port at 9600 bps
  Serial.begin(9600); 

  // Set pin states of the encoder
  pinMode(ENC_IN_RIGHT_A , INPUT_PULLUP);
  pinMode(ENC_IN_RIGHT_B , INPUT);

  // Every time the pin goes high, this is a pulse
  attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_pulse, RISING);
  
}

void loop() {

  // Record the time
  currentMillis = millis();

  // If one second has passed, print the number of pulses
  if (currentMillis - previousMillis > interval) {

    previousMillis = currentMillis;

    // Calculate revolutions per minute
    rpm_right = (float)(right_wheel_pulse_count * 60 / ENC_COUNT_REV);
    ang_velocity_right = rpm_right * rpm_to_radians;   
    ang_velocity_right_deg = ang_velocity_right * rad_to_deg;
    
    Serial.print(" Pulses: ");
    Serial.println(right_wheel_pulse_count);
    Serial.print(" Speed: ");
    Serial.print(rpm_right);
    Serial.println(" RPM");
    Serial.print(" Angular Velocity: ");
    Serial.print(rpm_right);
    Serial.print(" rad per second");
    Serial.print("\t");
    Serial.print(ang_velocity_right_deg);
    Serial.println(" deg per second");
    Serial.println();

    right_wheel_pulse_count = 0;
  
  }
}

// Increment the number of pulses by 1
void right_wheel_pulse() {
  
  // Read the value for the encoder for the right wheel
  int val = digitalRead(ENC_IN_RIGHT_B);

  if(val == LOW) {
    Direction_right = false; // Reverse
  }
  else {
    Direction_right = true; // Forward
  }
  
  if (Direction_right) {
    right_wheel_pulse_count++;
  }
  else {
    right_wheel_pulse_count--;
  }
}

Compile the code by clicking the green checkmark in the upper-left of the IDE window.

Connect the Arduino board to your personal computer using the USB cord.

Load the code we just wrote to your Arduino board.

Open the Serial Monitor.

Here is the output when I rotate the motor forward:

fw_vel

Here is the output when I rotate the motor in reverse.

rev_vel

Calculating Linear Velocity

Now that you know how to calculate the angular velocity of a wheel, you can calculate the linear velocity of that wheel if you know it’s radius. Here is the equation:

(Linear Velocity in meters per second) = (Radius of the wheel in meters) * (Angular Velocity in radians per second)

This equation above is commonly written as:

v = r * ω

That’s it. Keep building!

Calculate Pulses per Revolution for a DC Motor With Encoder

In this tutorial, we will learn how to calculate the number of pulses per 360 degree revolution for a DC motor with a built-in encoder. The motor that we will work with looks like the following image, however you can use any motor that looks similar to it:

1_dc_motor_encoder_wheels

Real-World Applications

When we know the number of pulses that an encoder outputs for each 360-degree turn of a motor, we can use that information to calculate the angular velocity of the wheels (in radians per second). 

When we know the angular velocity of the wheels on a robot and the radius of the wheels, we can calculate how fast the robot is moving (i.e. speed) as well as the distance a robot has traveled in a given unit of time. This information is important for helping us determine where a robot is in a particular environment.

Prerequisites

  • You have the Arduino IDE (Integrated Development Environment) installed on either your PC (Windows, MacOS, or Linux).

You Will Need

This section is the complete list of components you will need for this project (#ad).

OR

  • Self-Balancing Car Kit (which includes everything above and more…Elegoo and Osoyoo are good brands you can find on Amazon.com)

Disclosure (#ad): As an Amazon Associate I earn from qualifying purchases.

What is a Pulse?

When a motor with a built-in encoder rotates, it generates pulses, which are alternating electrical signals of high voltage and low voltage. Each time the signal goes from low to high (i.e. rising), we count that as a single pulse.

time-intervalJPG

Our goal is to take our motor and measure the number of encoder pulses (often referred to as “ticks”) it generates in a single 360 degree turn of the motor.

Set Up the Hardware

The first thing we need to do is set up the hardware.

Here is the wiring diagram:

jgb37_dc_motor_with_encoder-1
  • The Ground pin of the motor connects to GND of the Arduino.
  • Encoder A (sometimes labeled C1) of the motor connects to pin 2 of the Arduino. Pin 2 of the Arduino will record every time there is a rising digital signal from Encoder A.
  • Encoder B (sometimes labeled C2) of the motor connects to pin 4 of the Arduino. The signal that is read off pin 4 on the Arduino will determine if the motor is moving forward or in reverse. We’re not going to use this pin in this tutorial, but we will use it in a future tutorial.
  • The VCC pin of the motor connects to the 5V pin of the Arduino. This pin is responsible for providing power to the encoder.
  • For this project, you don’t need to connect the motor pins (+ and – terminals) to anything since you will be turning the motor manually with your hand.

Write and Load the Code

Now we’re ready to calculate the number of encoder pulses per revolution. Open the Arduino IDE, and write the following program. The name of my program is pulses_per_revolution_counter.ino.

/*
 * Author: Automatic Addison
 * Website: https://automaticaddison.com
 * Description: Count the number of encoder pulses per revolution.  
 */

// Encoder output to Arduino Interrupt pin. Tracks the pulse count.
#define ENC_IN_RIGHT_A 2

// Keep track of the number of right wheel pulses
volatile long right_wheel_pulse_count = 0;

void setup() {

  // Open the serial port at 9600 bps
  Serial.begin(9600); 

  // Set pin states of the encoder
  pinMode(ENC_IN_RIGHT_A , INPUT_PULLUP);

  // Every time the pin goes high, this is a pulse
  attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_pulse, RISING);
  
}

void loop() {
 
    Serial.print(" Pulses: ");
    Serial.println(right_wheel_pulse_count);  
}

// Increment the number of pulses by 1
void right_wheel_pulse() {
  right_wheel_pulse_count++;
}

Compile the code by clicking the green checkmark in the upper-left of the IDE window.

Connect the Arduino board to your personal computer using the USB cord.

Load the code we just wrote to your Arduino board.

Now, follow the following steps in the image below.

open-serial-monitorJPG

When you open the Serial Monitor, the pulse count should be 0.

2_starting_pulses

Using your hand, rotate the motor a complete 360-degree turn.

Here is the output. We can see that there were 620 pulses generated. 

3-ending-pulses

Thus, this motor generates 620 pulses per revolution.

That’s it. Keep building!

How to Set Up a Camera for NVIDIA Jetson Nano

In this tutorial, we will connect a camera to an NVIDIA Jetson Nano.

Prerequisites

You Will Need

This section is the complete list of components you will need for this project (#ad).

2021-04-07-09.40.12

Disclosure (#ad): As an Amazon Associate I earn from qualifying purchases.

Connect the Camera to the Jetson Nano

Make sure the Jetson Nano is completely off, and no power is connected to it.

Grab the camera.

2021-04-07-09.40.46

Lift the plastic tabs of the CSI connector that is closest to the barrel jack (Camera 0). 

Slide the ribbon cable fully into the connector so that it is not tilted. The blue marking should face towards the outside of the board, away from the heat sink. The ribbon cable contacts need to face towards the heat sink.

Hold the ribbon cable still while carefully and gently push down on the plastic tabs to fasten the camera into place.

You should be able to pull gently on the camera without the camera popping out of the latch.

Test Your Camera

Turn on your Jetson Nano.

Open a new terminal window, and type:

ls /dev/video0

If you see output like this, it means your camera is connected.

2021-04-07-09.50.35

Take a Photo

Now open a new terminal window, and move it to the edge of your desktop.

Type the following command. You can change the value of orientation (0-3) to get the right orientation of your camera.

nvgstcapture-1.0 --orientation=2
2021-04-07-10.17.27

Press CTRL+C exit.

Test Python Setup (Optional)

Let’s see if we can run a Python script that uses the camera.

Open a new terminal window, and clone the repository created by JetsonHacksNano.

git clone https://github.com/JetsonHacksNano/CSI-Camera.git

Change to the new directory.

cd CSI-Camera

Type this command. This is all a single command:

gst-launch-1.0 nvarguscamerasrc sensor_id=0 ! 'video/x-raw(memory:NVMM),width=3280, height=2464, framerate=21/1, format=NV12' ! nvvidconv flip-method=2 ! 'video/x-raw, width=816, height=616' ! nvvidconv ! nvegltransform ! nveglglessink -e

Press CTRL + C to shut it down.

Install NumPy.

sudo apt-get update
sudo apt install python3-numpy

Install libcanberra.

sudo apt install libcanberra-gtk-module

Run the face detection python script.

python3 face_detect.py

Here is my output:

2021-04-07-10.42.11-1

If the output doesn’t turn out like you want it to, open the face_detect.py script.

gedit face_detect.py

Note: if you don’t have gedit installed, type:

sudo apt-get install gedit

Edit the flip-method parameter:

def gstreamer_pipeline(
    …
    framerate=21,
    flip_method=2,

Here are the options for the flip_method parameter:

  • Default: 0, “none”
  • (0): none – Identity (no rotation)
  • (1): counterclockwise – Rotate counter-clockwise 90 degrees
  • (2): rotate-180 – Rotate 180 degrees
  • (3): clockwise – Rotate clockwise 90 degrees
  • (4): horizontal-flip – Flip horizontally
  • (5): upper-right-diagonal – Flip across upper right/lower left diagonal
  • (6): vertical-flip – Flip vertically
  • (7): upper-left-diagonal – Flip across upper left/low

Here is the full code for face_detect.py (credit: JetsonHacks)

# MIT License
# Copyright (c) 2019 JetsonHacks
# See LICENSE for OpenCV license and additional information

# https://docs.opencv.org/3.3.1/d7/d8b/tutorial_py_face_detection.html
# On the Jetson Nano, OpenCV comes preinstalled
# Data files are in /usr/sharc/OpenCV
import numpy as np
import cv2

# gstreamer_pipeline returns a GStreamer pipeline for capturing from the CSI camera
# Defaults to 1280x720 @ 30fps
# Flip the image by setting the flip_method (most common values: 0 and 2)
# display_width and display_height determine the size of the window on the screen


def gstreamer_pipeline(
    capture_width=3280,
    capture_height=2464,
    display_width=820,
    display_height=616,
    framerate=21,
    flip_method=2,
):
    return (
        "nvarguscamerasrc ! "
        "video/x-raw(memory:NVMM), "
        "width=(int)%d, height=(int)%d, "
        "format=(string)NV12, framerate=(fraction)%d/1 ! "
        "nvvidconv flip-method=%d ! "
        "video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! "
        "videoconvert ! "
        "video/x-raw, format=(string)BGR ! appsink"
        % (
            capture_width,
            capture_height,
            framerate,
            flip_method,
            display_width,
            display_height,
        )
    )


def face_detect():
    face_cascade = cv2.CascadeClassifier(
        "/usr/share/opencv4/haarcascades/haarcascade_frontalface_default.xml"
    )
    eye_cascade = cv2.CascadeClassifier(
        "/usr/share/opencv4/haarcascades/haarcascade_eye.xml"
    )
    cap = cv2.VideoCapture(gstreamer_pipeline(), cv2.CAP_GSTREAMER)
    if cap.isOpened():
        cv2.namedWindow("Face Detect", cv2.WINDOW_AUTOSIZE)
        while cv2.getWindowProperty("Face Detect", 0) >= 0:
            ret, img = cap.read()
            gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
            faces = face_cascade.detectMultiScale(gray, 1.3, 5)

            for (x, y, w, h) in faces:
                cv2.rectangle(img, (x, y), (x + w, y + h), (255, 0, 0), 2)
                roi_gray = gray[y : y + h, x : x + w]
                roi_color = img[y : y + h, x : x + w]
                eyes = eye_cascade.detectMultiScale(roi_gray)
                for (ex, ey, ew, eh) in eyes:
                    cv2.rectangle(
                        roi_color, (ex, ey), (ex + ew, ey + eh), (0, 255, 0), 2
                    )

            cv2.imshow("Face Detect", img)
            keyCode = cv2.waitKey(30) & 0xFF
            # Stop the program on the ESC key
            if keyCode == 27:
                break

        cap.release()
        cv2.destroyAllWindows()
    else:
        print("Unable to open camera")


if __name__ == "__main__":
    face_detect()

Press CTRL+C to stop the script.

Test C++ Setup (Optional)

Open simple_camera.cpp and edit the flip_method in the main function if necessary.

gedit simple_camera.cpp

int main()
{
…
    int framerate = 60 ;
    int flip_method = 2;

Save the file and close it.

Compile simple_camera.cpp. You can copy and paste this command.

g++ -std=c++11 -Wall -I/usr/include/opencv4 simple_camera.cpp -L/usr/lib/aarch64-linux-gnu -lopencv_core -lopencv_highgui -lopencv_videoio -o simple_camera

Run simple_camera.cpp

./simple_camera
2021-04-07-10.50.51

Press ESC when you’re done.

To shutdown the computer, type:

sudo shutdown -h now

Here is the full code for simple_camera.cpp:

// simple_camera.cpp
// MIT License
// Copyright (c) 2019 JetsonHacks
// See LICENSE for OpenCV license and additional information
// Using a CSI camera (such as the Raspberry Pi Version 2) connected to a 
// NVIDIA Jetson Nano Developer Kit using OpenCV
// Drivers for the camera and OpenCV are included in the base image

// #include <iostream>
#include <opencv2/opencv.hpp>
// #include <opencv2/videoio.hpp>
// #include <opencv2/highgui.hpp>

std::string gstreamer_pipeline (int capture_width, int capture_height, int display_width, int display_height, int framerate, int flip_method) {
    return "nvarguscamerasrc ! video/x-raw(memory:NVMM), width=(int)" + std::to_string(capture_width) + ", height=(int)" +
           std::to_string(capture_height) + ", format=(string)NV12, framerate=(fraction)" + std::to_string(framerate) +
           "/1 ! nvvidconv flip-method=" + std::to_string(flip_method) + " ! video/x-raw, width=(int)" + std::to_string(display_width) + ", height=(int)" +
           std::to_string(display_height) + ", format=(string)BGRx ! videoconvert ! video/x-raw, format=(string)BGR ! appsink";
}

int main()
{
    int capture_width = 1280 ;
    int capture_height = 720 ;
    int display_width = 1280 ;
    int display_height = 720 ;
    int framerate = 60 ;
    int flip_method = 2 ;

    std::string pipeline = gstreamer_pipeline(capture_width,
	capture_height,
	display_width,
	display_height,
	framerate,
	flip_method);
    std::cout << "Using pipeline: \n\t" << pipeline << "\n";
 
    cv::VideoCapture cap(pipeline, cv::CAP_GSTREAMER);
    if(!cap.isOpened()) {
	std::cout<<"Failed to open camera."<<std::endl;
	return (-1);
    }

    cv::namedWindow("CSI Camera", cv::WINDOW_AUTOSIZE);
    cv::Mat img;

    std::cout << "Hit ESC to exit" << "\n" ;
    while(true)
    {
    	if (!cap.read(img)) {
		std::cout<<"Capture read error"<<std::endl;
		break;
	}
	
	cv::imshow("CSI Camera",img);
	int keycode = cv::waitKey(30) & 0xff ; 
        if (keycode == 27) break ;
    }

    cap.release();
    cv::destroyAllWindows() ;
    return 0;
}

That’s it. Keep building!

References

This tutorial was especially helpful.