How to Publish Wheel Encoder Tick Data Using ROS and Arduino

In this tutorial, we will create a program using ROS and Arduino to publish the tick data from the encoders of each motor of a two-wheeled robot. 

The microcontroller we will use is the Nvidia Jetson Nano, but you can also use an Ubuntu-enabled Raspberry Pi.

We will interface Arduino with ROS so we can publish the tick counts for the left wheel and right wheel to ROS topics. The name of this node will be tick_publisher.

Why Publish Wheel Encoder Tick Data

Tick data from wheel encoders helps us determine how much each wheel (both the left and right wheels) has rotated. Since we know the radius of each wheel, we can use the tick data and the wheel radius data to determine the distance traveled by each wheel. Here is the equation for that: 

Distance a wheel has traveled = 2 * pi * radius of the wheel * (number of ticks / number of ticks per revolution)

Knowing the distance traveled by each wheel helps us determine where the robot is located in its environment relative to some starting location. This process is known as odometry

The first time you were exposed to the word “odometry” was likely when you began driving a car. Right behind your steering wheel is typically your odometer. The odometer of your car measures the distance traveled by the vehicle relative to some starting point where the car was first driven. Odometry in robotics works the same way.

odometer_car_dashboard
A typical odometer on a car’s dashboard

Real-World Applications

2021-05-13-20.47.13
You can see that a robotic vacuum cleaner has the same two-wheeled differential drive setup as the robot I’m currently working with in this tutorial.

This project has a number of real-world applications: 

  • Indoor Delivery Robots
  • Room Service Robots
  • Mapping of Underground Mines, Caves, and Hard-to-Reach Environments
  • Robot Vacuums
  • Order Fulfillment
  • Factories

Prerequisites

2021-05-11-19.38.06

You Will Need

  • Arduino Uno (Elegoo Uno works just fine and is cheaper than the regular Arduino)

Install Arduino on Your Jetson Nano

To get started, turn on your Jetson Nano.

Let’s download the Arduino IDE (you’ll have to download the Arduino IDE directly from the Arduino website if you are using Ubuntu on the Raspberry Pi).

Open a new terminal window, and type the following commands, one right after the other.

git clone https://github.com/JetsonHacksNano/installArduinoIDE.git
cd installArduinoIDE
./installArduinoIDE.sh

We are installing the Linux ARM 64 bits version.

Wait a few moments, and then reboot your computer.

sudo reboot

When you restart your computer, you will see an Arduino icon on the desktop of your Jetson Nano.

Open a new terminal window, and shut down your Jetson Nano.

sudo shutdown -h now

Plug the Arduino into the USB port of your Jetson Nano.

Turn on your Jetson Nano.

Open the Arduino IDE by double-clicking the icon on the desktop of your Jetson Nano.

Go to Tools -> Board, and select Arduino/Genuino Uno.

Go to Tools -> Port, and select the Serial port that is connected to your Arduino/Genuino Uno. In my case, it is /dev/ttyACM0.

Now open the Blink sketch again. Go to File – > Examples -> 01.Basics, and choose Blink.

Click the Upload button…the right arrow in the upper left of your screen.

The LED on your Arduino should be blinking! If it is not, go back to the beginning of this tutorial and follow the steps carefully.

To turn off the blinking light, open up a new sketch (Go to File -> New), and upload it to your board.

Integrate Arduino With ROS 

Getting Started

Now that we know Arduino is working, we need to integrate it with ROS. Here are the official instructions. I’ll walk you through the steps below.

Let’s install the necessary packages. 

Quit the Arduino IDE. Then type the following commands in a new terminal window (this software will take a while to download so be patient):

sudo apt-get install ros-melodic-rosserial-arduino
sudo apt-get install ros-melodic-rosserial

Open the IDE and go to File -> Preferences. Make a note of the Sketchbook location. Mine is:

/home/automaticaddison/Arduino

Quit the Arduino IDE.

Open a new terminal window, and go to the sketchbook location you noted above. I’ll type:

cd Arduino

Type the dir command to see the list of folders.

dir

Go to the libraries directory.

cd libraries
rm -rf ros_lib

Within that directory, run the following command to build the Arduino library that will be used by ROS (don’t leave out that period that comes at the end of the command):

rosrun rosserial_arduino make_libraries.py .

Type the dir command to see the list of folders. You should now see the ros_lib library.

dir

Make sure the Arduino IDE is closed. Now open it again.

Blink an LED on the Arduino Using ROS

In this example, Arduino is going to be considered a Subscriber node. It will subscribe to a topic called toggle_led. Publishing a message to that topic causes the LED to turn on. Publishing a message to the topic again causes the LED to turn off. 

Go to File -> Examples -> ros_lib and open the Blink sketch.

Before the nh.initNode(); line, add the following code:

nh.getHardware()->setBaud(115200);

Now we need to upload the code to Arduino. Make sure your Arduino is plugged into the USB port on your Jetson Nano (or whatever microcontroller you are using).

Upload the code to your Arduino using the right arrow button in the upper left of your screen. When you upload the code, your Arduino should flicker a little bit.

Note: I created a new Arduino sketch and saved it to /home/automaticaddison/Documents as “blink_ros_arduino_test”. This is not required.

Quit the Arduino IDE.

Open a new terminal window and type:

roscore

In a new terminal window, launch the ROS serial server. This command is explained here on the ROS website. It is necessary to complete the integration between ROS and Arduino:

cd ~/catkin_ws
rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=115200

Now let’s turn on the LED by publishing a single empty message to the /toggle_led topic. Open a new terminal window and type:

rostopic pub toggle_led std_msgs/Empty --once

The LED on the Arduino should turn on. 

Now press the Up arrow in the terminal and press ENTER to run this code again. You should see the LED turn off. You might also see a tiny yellow light blinking as well. Just ignore that one…you’re interested in the big yellow light that you’re able to turn off and on by publishing single messages to the /toggle_led topic.

2021-05-11-16.05.51
2021-05-11-16.06.02

You can see the active topics by typing.

rostopic list

Another good example to check out is a publisher and subscriber. You can see this by going to:

File -> Examples -> ros_lib -> pubsub

This ROS node will blink an LED and publish a “Hello World” message to a topic named chatter.

That’s it! You have now seen how you can integrate Arduino with ROS. To turn off your Arduino, all you need to do is disconnect it after you shut down your Jetson Nano.

Create a Tick Publisher Node

Now we want to write a tick publisher node. This ROS node will publish the accumulated tick count for the left and right motors of the robot at regular intervals.

Set Up the Hardware

Let’s revisit this tutorial to set up the hardware.

Here is the wiring diagram for the left motor:

jgb37_dc_motor_with_encoder-2
  • The Ground pin of the motor connects to GND of the Arduino. I’m using a 400-point solderless breadboard that I bought on Amazon.com to facilitate this connection.
  • 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 the right motor:

  • The Ground pin of the motor connects to GND of the Arduino.
  • Encoder A (sometimes labeled C1) of the motor connects to pin 3 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 11 of the Arduino. The signal that is read off pin 11 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.

Write the Code

Now we’re ready to calculate the accumulated ticks for each wheel.

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

/*
 * Author: Automatic Addison
 * Website: https://automaticaddison.com
 * Description: Calculate the accumulated ticks for each wheel using the 
 * built-in encoder (forward = positive; reverse = negative) 
 */

// Encoder output to Arduino Interrupt pin. Tracks the tick count.
#define ENC_IN_LEFT_A 2
#define ENC_IN_RIGHT_A 3

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

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

// Minumum and maximum values for 16-bit integers
const int encoder_minimum = -32768;
const int encoder_maximum = 32767;

// Keep track of the number of wheel ticks
volatile int left_wheel_tick_count = 0;
volatile int right_wheel_tick_count = 0;

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

void setup() {

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

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

  // Every time the pin goes high, this is a tick
  attachInterrupt(digitalPinToInterrupt(ENC_IN_LEFT_A), left_wheel_tick, RISING);
  attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_tick, RISING);
}

void loop() {

  // Record the time
  currentMillis = millis();

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

    Serial.println("Number of Ticks: ");
    Serial.println(right_wheel_tick_count);
    Serial.println(left_wheel_tick_count);
    Serial.println();
  }
}

// Increment the number of ticks
void right_wheel_tick() {
  
  // 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) {
    
    if (right_wheel_tick_count == encoder_maximum) {
      right_wheel_tick_count = encoder_minimum;
    }
    else {
      right_wheel_tick_count++;  
    }    
  }
  else {
    if (right_wheel_tick_count == encoder_minimum) {
      right_wheel_tick_count = encoder_maximum;
    }
    else {
      right_wheel_tick_count--;  
    }   
  }
}

// Increment the number of ticks
void left_wheel_tick() {
  
  // Read the value for the encoder for the left wheel
  int val = digitalRead(ENC_IN_LEFT_B);

  if(val == LOW) {
    Direction_left = true; // Reverse
  }
  else {
    Direction_left = false; // Forward
  }
  
  if (Direction_left) {
    if (left_wheel_tick_count == encoder_maximum) {
      left_wheel_tick_count = encoder_minimum;
    }
    else {
      left_wheel_tick_count++;  
    }  
  }
  else {
    if (left_wheel_tick_count == encoder_minimum) {
      left_wheel_tick_count = encoder_maximum;
    }
    else {
      left_wheel_tick_count--;  
    }   
  }
}

Upload the program to the Arduino.

If you open the serial monitor, you will see the accumulated tick count. Once the tick count gets outside the range of what a 16-bit integer can handle, it rolls over to either the minimum -32,768 or maximum 32,767 of the range.

1-tick-counter

Convert the Code to a ROS Node

Now that we see how to print tick counts for the right and left motors, let’s convert the code from the previous section into a ROS node. We want our node to publish tick counts for the right and left wheels of the robot to ROS topics named right_ticks and left_ticks.

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

/*
 * Author: Automatic Addison
 * Website: https://automaticaddison.com
 * Description: ROS node that publishes the accumulated ticks for each wheel
 * (right_ticks and left_ticks topics) using the built-in encoder 
 * (forward = positive; reverse = negative) 
 */

#include <ros.h>
#include <std_msgs/Int16.h>

// Handles startup and shutdown of ROS
ros::NodeHandle nh;

// Encoder output to Arduino Interrupt pin. Tracks the tick count.
#define ENC_IN_LEFT_A 2
#define ENC_IN_RIGHT_A 3

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

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

// Minumum and maximum values for 16-bit integers
const int encoder_minimum = -32768;
const int encoder_maximum = 32767;

// Keep track of the number of wheel ticks
std_msgs::Int16 right_wheel_tick_count;
ros::Publisher rightPub("right_ticks", &right_wheel_tick_count);

std_msgs::Int16 left_wheel_tick_count;
ros::Publisher leftPub("left_ticks", &left_wheel_tick_count);

// 100ms interval for measurements
const int interval = 100;
long previousMillis = 0;
long currentMillis = 0;

// Increment the number of ticks
void right_wheel_tick() {
  
  // 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) {
    
    if (right_wheel_tick_count.data == encoder_maximum) {
      right_wheel_tick_count.data = encoder_minimum;
    }
    else {
      right_wheel_tick_count.data++;  
    }    
  }
  else {
    if (right_wheel_tick_count.data == encoder_minimum) {
      right_wheel_tick_count.data = encoder_maximum;
    }
    else {
      right_wheel_tick_count.data--;  
    }   
  }
}

// Increment the number of ticks
void left_wheel_tick() {
  
  // Read the value for the encoder for the left wheel
  int val = digitalRead(ENC_IN_LEFT_B);

  if(val == LOW) {
    Direction_left = true; // Reverse
  }
  else {
    Direction_left = false; // Forward
  }
  
  if (Direction_left) {
    if (left_wheel_tick_count.data == encoder_maximum) {
      left_wheel_tick_count.data = encoder_minimum;
    }
    else {
      left_wheel_tick_count.data++;  
    }  
  }
  else {
    if (left_wheel_tick_count.data == encoder_minimum) {
      left_wheel_tick_count.data = encoder_maximum;
    }
    else {
      left_wheel_tick_count.data--;  
    }   
  }
}

void setup() {

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

  // Every time the pin goes high, this is a tick
  attachInterrupt(digitalPinToInterrupt(ENC_IN_LEFT_A), left_wheel_tick, RISING);
  attachInterrupt(digitalPinToInterrupt(ENC_IN_RIGHT_A), right_wheel_tick, RISING);

  // ROS Setup
  nh.getHardware()->setBaud(115200);
  nh.initNode();
  nh.advertise(rightPub);
  nh.advertise(leftPub);
}

void loop() {
  
  // Record the time
  currentMillis = millis();

  // If 100ms have passed, print the number of ticks
  if (currentMillis - previousMillis > interval) {
    
    previousMillis = currentMillis;
    
    rightPub.publish( &right_wheel_tick_count );
    leftPub.publish( &left_wheel_tick_count );
    nh.spinOnce();
  }
}

Upload the code to your Arduino using the right arrow button in the upper left of your screen. 

Quit the Arduino IDE.

Run the Tick Publisher

Open a new terminal window and type:

roscore

In a new terminal window, launch the ROS serial server. 

rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0 _baud:=115200
2021-05-11-22.36.41

Open a new terminal window, and check out the active ROS topics.

rostopic list
2021-05-11-22.34.09

You can see the right wheel tick count by typing the following command:

rostopic echo /right_ticks

You can see the left wheel tick count by typing the following command:

rostopic echo /left_ticks

Spin the wheels, and see the numbers go up and down.

2021-05-11-22.35.57
2021-05-11-22.35.50

Create a Launch File

Let’s start accumulating our ROS nodes in a launch file to make things easier for us down the road.

Open a new terminal window, and type the following command.

cd ~/catkin_ws/src/jetson_nano_bot

Create a package. 

catkin_create_pkg launch_jetson_nano_bot rospy roscpp std_msgs sensor_msgs geometry_msgs tf

Move to the package.

cd launch_jetson_nano_bot

Create a folder to contain launch files.

mkdir launch

Now open a new terminal and move to your catkin workspace.

cd ~/catkin_ws/

Compile the package.

catkin_make --only-pkg-with-deps  launch_jetson_nano_bot

Move inside the package.

roscd launch_jetson_nano_bot

Go inside the CMakeLists.txt file.

gedit CMakeLists.txt

Remove the hashtag on line 5 to make sure that C++11 support is enabled.

Save and close the file.

Move into the launch folder.

cd launch

Create a new launch file.

gedit jetson_nanobot.launch

Add the following code to a launch file.

<launch>
  <node pkg="rosserial_python" type="serial_node.py" name="serial_node">
    <param name="port" value="/dev/ttyACM0"/>
    <param name="baud" value="115200"/>
  </node>
</launch>

Save the file, and close it.

Change the permissions of the launch file we just created. It will ask you for your password.

sudo chmod +x jetson_nanobot.launch

Open a new terminal window, and go to the home directory.

cd

Launch the launch file.

roslaunch launch_jetson_nano_bot jetson_nanobot.launch

If you open a new terminal window, and type the following command, you will be able to see the active topics.

rostopic list

How to Move the Turtlesim Robot to Goal Locations – ROS

In this tutorial, we will build ROS nodes to move the turtlesim robot to goal locations.

Real-World Applications

This project has a number of real-world applications: 

  • Indoor Delivery Robots
  • Mapping of Underground Mines, Caves, and Hard-to-Reach Environments
  • Robot Vacuums
  • Order Fulfillment
  • Factories

You can imagine the turtlesim robot is like having an aerial view of a mobile robot moving around on a factory floor. We want to be able to navigate the robot around the floor to do its work, and in order to navigate it, we imagine the factory floor is like an x-y graph (e.g. like the image below from this tutorial). All we would need to do is enter an x-y coordinate, and the robot would move to that goal location (i.e. waypoint).

state-space-model-4JPG

Prerequisites

Run the Turtlesim Simulation

To run the turtlesim simulation, open a terminal window and launch ROS.

roscore

See what nodes are available to run by typing:

rosrun turtlesim <TAB><TAB>
1-nodes-available-to-run

Open another terminal window, and launch the turtlesim_node.

rosrun turtlesim turtlesim_node

Let’s steer the robot.

rosrun rqt_robot_steering rqt_robot_steering

You should see a window pop up. 

2-rqt-robot-steering

You’ll note that the default ROS topic is the /cmd_vel topic. This topic is where the rqt_robot_steering node will publish Twist messages. A Twist message in ROS is a special kind of topic that consists of the x, y, and z components of the linear and angular velocity.

Go back to the terminal window, and let’s see what topic the turtlesim node is subscribed to.

rostopic list

The turtlesim node gets its velocity commands from the /turtle1/cmd_vel topic.

List all the active nodes.

rosnode list

Find out what the /turtlesim node is subscribing to.

rosnode info /turtlesim
4-ros-node-info-turtlesim

You can see that the /turtlesim node is subscribing to /turtle1/cmd_vel

Let’s find out more about this topic.

rostopic info /turtle1/cmd_vel

You can see that the type of message that passes through the /turtle1/cmd_vel topic is a Twist message.

3-rostopic-list-info

Let’s change the topic name of the rqt_steering GUI to /turtle1/cmd_vel.

6-change-topic-name

If you adjust the sliders for the linear and angular velocities, you will see the turtle move accordingly because the GUI is publishing linear and angular velocity values to the /turtle1/cmd_vel topic. The /turtlesim node reads the velocity values on this topic and then moves accordingly.

In a real-world robot, we can see how the rqt_steering node is useful. We can publish velocity commands to the /cmd_vel topic. A motor controller that subscribes to the /cmd_vel topic can convert those velocity commands into motor commands to make the robot drive accordingly.

Create a Package

Now that we’ve gotten reacquainted with turtlesim, let’s see how we get into the purpose of this tutorial: create a ROS node to move the turtlesim robot to a goal location.

The first thing we need to do is create a package.

Open a new terminal window.

Go to the src folder of your catkin_ws folder.

cd ~/catkin_ws/src
catkin_create_pkg go_to_goal_turtlesim std_msgs rospy roscpp

Move inside the package.

cd go_to_goal_turtlesim 

Open the CMakeLists.txt file. 

gedit CMakeLists.txt

Enable C++11 support be removing the hashtag # on line 5 by uncommenting the add_compile_option… line.

Here is how that should look now.

7-uncomment-line-5

How to Move the Robot to a Desired X Coordinate

Create the ROS Node

Now let’s create a program (i.e. ROS Node) that will take the coordinates of the turtle as input and will output a velocity command as a Twist message. The velocity command will be calculated so as to get the turtlesim robot to move to a goal x coordinate that can be any number from 0 to 11.

In this first node, we will create a ROS node to move the turtlesim robot to a goal x coordinate.

The first thing we need to do is to open a new terminal window.

Move to the src folder of the go_to_goal_turtlesim package.

cd ~/catkin_ws/src/go_to_goal_turtlesim/src

Create a new C++ program called go_to_goal_x.cpp.

gedit go_to_goal_x.cpp

Add the following code to the file, and then click Save.

/// @file go_to_goal_x.cpp
/// @author Addison Sears-Collins
/// @date May 4, 2021
/// 
/// This program takes the coordinates of the turtlesim robot as input
/// and outputs a velocity command as a Twist message. The velocity command
/// will be calculated so as to get the turtlesim robot to move to a goal 
/// x coordinate that can be any number from 0 to 11.

#include <cstdlib> // Use for the absolute value method abs()
#include <iostream> // Enables command line input and output

#include "ros/ros.h" // Necessary header files for ROS
#include "geometry_msgs/Twist.h" // Twist messages (linear & angular velocity)
#include "geometry_msgs/Pose2D.h" // x, y position and theta orientation
#include "turtlesim/Pose.h" // x, y, theta, linear & angular velocity

// Remove the need to use std:: prefix
using namespace std;

// Key variable declarations 
geometry_msgs::Twist velCommand; // Linear and angular velocity in m/s 
geometry_msgs::Pose2D current; // Current x, y, and theta 
geometry_msgs::Pose2D desired; // Desired x, y, and theta 

// Goal x-value, which can be any number from 0 to 11 (inclusive)
const double GOAL = 1.3;

// The gain K, which is used to calculate the linear velocity
const double K_l = 1.0;

// The distance threshold in meters that will determine when 
// the turtlesim robot successfully reaches the goal.
const double distanceTolerance = 0.1;

// Initialized variables and take care of other setup tasks
void setup() {

  // Desired x goal coordinate
  desired.x = GOAL;
  
  // Initialize the Twist message.
  // Initial linear and angular velocities are 0 m/s and rad/s, respectively.
  velCommand.linear.x = 0.0;
  velCommand.linear.y = 0.0;
  velCommand.linear.z = 0.0;
  velCommand.angular.x = 0.0;
  velCommand.angular.y = 0.0;
  velCommand.angular.z = 0.0;
}

// Get the distance between the current x coordinate and 
// the desired x coordinate.
double getDistanceToGoal() {
  return desired.x - current.x;
}

// If we haven't yet reached the goal, set the velocity value.
// Otherwise, stop the robot.
void setVelocity() {
  if (abs(getDistanceToGoal()) > distanceTolerance) {

    // The magnitude of the robot's velocity is directly
    // proportional to the distance the robot is from the 
    // goal.
    velCommand.linear.x = K_l * getDistanceToGoal();
  }
  else {
    cout << "Goal has been reached!" << endl << endl;
    velCommand.linear.x = 0;
  }
}

// This callback function updates the current position and 
// orientation of the robot. 
void updatePose(const turtlesim::PoseConstPtr &currentPose) {
  current.x = currentPose->x;
  current.y = currentPose->y;
  current.theta = currentPose->theta;
}

int main(int argc, char **argv) {

  setup();  

  // Initiate ROS
  ros::init(argc, argv, "go_to_goal_x");
    
  // Create the main access point to communicate with ROS
  ros::NodeHandle node;

  // Subscribe to the robot's pose
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are received that are not able to be
  // processed quickly enough.
  // Every time a new pose is received, update the robot's pose.
  ros::Subscriber currentPoseSub =
    node.subscribe("turtle1/pose", 0, updatePose);

  // Publish velocity commands to a topic.
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are received that are not able to be
  // processed quickly enough.
  ros::Publisher velocityPub =
    node.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 0);

  // Specify a frequency that want the while loop below to loop at
  // In this case, we want to loop 10 cycles per second
  ros::Rate loop_rate(10); 

  // Keep running the while loop below as long as the ROS Master is active. 
  while (ros::ok()) {

    // Here is where we call the callbacks that need to be called.
    ros::spinOnce();

    // After we call the callback function to update the robot's pose, we 
    // set the velocity values for the robot.
    setVelocity();

    // Publish the velocity command to the ROS topic
    velocityPub.publish(velCommand);

    // Print the output to the console
    cout << "Current x = " << current.x << endl
         << "Desired x = " << desired.x <<  endl
         << "Distance to Goal = " << getDistanceToGoal() << " m" << endl
         << "Linear Velocity (x) = " << velCommand.linear.x << " m/s" << endl
         << endl;

    // Sleep as long as we need to to make sure that we have a frequency of
    // 10Hz
    loop_rate.sleep();
  }

  return 0;
}

Now we need to add the C++ program we just wrote to the CMakeLists.txt file so that we can compile the program and launch it using ROS. Each time we write a new C++ ROS node, we have to make sure we add it to the CMakeLists.txt file.

cd ~/catkin_ws/src/go_to_goal_turtlesim
gedit CMakeLists.txt

Go to the bottom of the file.

Add the following lines.

8-add-lines-to-cmakelists-1

Save the file, and close it.

Go to the root of the workspace.

cd ~/catkin_ws

Compile the code.

catkin_make

Launch the ROS Node

Now let’s launch the ROS node we created in the last section.

Open a new terminal window.

Start ROS.

roscore

Open another terminal window, and launch the turtlesim_node.

rosrun turtlesim turtlesim_node
9-launch-turtlesim-node

We can see that the starting pose of the robot is as follows:

  • x = 5.544445
  • y = 5.544445
  • theta = 0.000000
10-starting-x-location
Sorry the font is so small.

Open another terminal window, and launch the go_to_goal_x node.

rosrun go_to_goal_turtlesim go_to_goal_x
11-launch-node
12-goal-has-been-reached
13-goal-has-been-reached

How to Move the Robot to a Desired X and Y Coordinate (i.e. Waypoint)

Create the Waypoint Publisher ROS Node

In this section, we’ll write a ROS node that can accept a waypoint (i.e. goal x and y coordinate) from the user. We want to then publish that goal location to a ROS topic named “waypoint”. 

We will later write a ROS node that can read the waypoint and navigate the turtlesim robot to that waypoint.

First, move to the src folder of the go_to_goal_turtlesim package.

cd ~/catkin_ws/src/go_to_goal_turtlesim/src

Create a new C++ program called waypoint_publisher.cpp.

gedit waypoint_publisher.cpp

Add the following code to the file, and then click Save.

/// @file waypoint_publisher.cpp
/// @author Addison Sears-Collins
/// @date May 6, 2021
/// 
/// This program takes the user's desired waypoint (i.e. goal location 
/// or x,y coordinate) as input and publishes it to a topic as a 
/// geometry_msgs/Pose2D data type.

#include <iostream> // Enables command line input and output

#include "ros/ros.h" // Necessary header files for ROS
#include "geometry_msgs/Pose2D.h" // x, y position and theta orientation

// Remove the need to use std:: prefix
using namespace std;

// Key variable declarations 
geometry_msgs::Pose2D waypoint; // Goal location ... x, y, and theta 

// Ask user for the desired waypoint...Where do you want the robot to move to?
void set_waypoint() {

  cout << "Where do you want the robot to go?" << endl; 
  cout << "Enter waypoint x: ";
  cin >> waypoint.x;
  cout << "Enter waypoint y: ";
  cin >> waypoint.y;
  cout << endl;  
}

int main(int argc, char **argv) { 

  // Initiate ROS
  ros::init(argc, argv, "waypoint_publisher");
    
  // Create the main access point to communicate with ROS
  ros::NodeHandle node;

  // Publish waypoint to a topic.
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are not able to be processed quickly enough.
  ros::Publisher waypointPub =
    node.advertise<geometry_msgs::Pose2D>("waypoint", 0);

  // Keep running the while loop below as long as the ROS Master is active. 
  while (ros::ok()) {

    // Ask the user where he wants the robot to go
    set_waypoint();

    // Publish the waypoint to the ROS topic
    waypointPub.publish(waypoint);

  }

  return 0;
}

Now we need to add the C++ program we just wrote to the CMakeLists.txt file.

cd ~/catkin_ws/src/go_to_goal_turtlesim
gedit CMakeLists.txt

Go to the bottom of the file.

Add the following lines.

14-add-lines-to-cmakelists

Save the file, and close it.

Go to the root of the workspace.

cd ~/catkin_ws

Compile the code.

catkin_make

Launch the ROS Node

Now let’s launch the ROS node we created in the last section.

Open a new terminal window.

Start ROS.

roscore

Open another terminal window, and launch the waypoint_publisher node.

rosrun go_to_goal_turtlesim waypoint_publisher

Here is what you will see in the terminal.

15-run-ros-node-1

Open a new terminal, and check out the active topics.

rostopic list

We can see one of the topics is /waypoint.

Let’s see what messages are passing through this topic.

rostopic echo /waypoint

You can see the pose of the robot (i.e. x, y, and theta values) is being published to the topic named /waypoint.

16-rostopic-echo-1
17-rostopic-echo-2

Create a ROS Node to Move the Robot to the Waypoint (i.e. X-Y Coordinate)

Now we need to create a ROS node that subscribes to the /waypoint topic and publishes a velocity command to move the turtle to the user’s desired waypoint (i.e. x-y coordinate).

Open a new terminal window.

Move to the src folder of the go_to_goal_turtlesim package.

cd ~/catkin_ws/src/go_to_goal_turtlesim/src

Create a new C++ program called go_to_goal_x_y.cpp.

gedit go_to_goal_x_y.cpp

Add the following code to the file, and then click Save.

/// @file go_to_goal_x_y.cpp
/// @author Addison Sears-Collins
/// @date May 7, 2021
/// 
/// This program takes the coordinates of the turtlesim robot and a goal 
/// waypoint (published by waypoint_publisher.cpp) as input and outputs 
/// a velocity command as a Twist message. The velocity command
/// will be calculated so as to get the turtlesim robot to move to the user's
/// desired goal waypoint (x, y coordinate). The x and y values can be any 
/// number from 0 to 11.

#include <cstdlib> // Use for the absolute value method abs()
#include <iostream> // Enables command line input and output

#include "ros/ros.h" // Necessary header files for ROS
#include "geometry_msgs/Twist.h" // Twist messages (linear & angular velocity)
#include "geometry_msgs/Pose2D.h" // x, y position and theta orientation
#include "turtlesim/Pose.h" // x, y, theta, linear & angular velocity

// Remove the need to use std:: prefix
using namespace std;

// Key variable declarations 
geometry_msgs::Twist velCommand; // Linear and angular velocity in m/s 
geometry_msgs::Pose2D current; // Current x, y, and theta 
geometry_msgs::Pose2D waypointGoal; // Waypoint x, y, and theta (the waypoint)
ros::Publisher velocityPub; // Object used for publishing velocity command

const double PI = 3.141592654;

// The gain K, which is used to calculate the linear velocity
const double K_l = 0.5;

// The gain K, which is used to calculate the angular velocity
const double K_a = 0.5;

// The distance threshold in meters that will determine when 
// the turtlesim robot successfully reaches the goal.
const double distanceTolerance = 0.1;

// The angle threshold in radians that will determine when 
// the turtlesim robot successfully reaches the goal.
const double angleTolerance = 0.1;

// This flag determines when the robot needs to either 
// move towards a waypoint or stop.
bool goToWaypoint = false;

// Initialized variables and take care of other setup tasks
void setup() {

  // We initialize with the default starting coordinate 
  // for the turtlesim simulator
  waypointGoal.x = 5.544445;
  waypointGoal.y = 5.544445;
  
  // Initialize the Twist message.
  // Initial linear and angular velocities are 0 m/s and rad/s, respectively.
  velCommand.linear.x = 0.0;
  velCommand.linear.y = 0.0;
  velCommand.linear.z = 0.0;
  velCommand.angular.x = 0.0;
  velCommand.angular.y = 0.0;
  velCommand.angular.z = 0.0;
}

// Get the distance between the current x,y coordinate and 
// the desired waypoint x,y coordinate.
double getDistanceToWaypoint() {
  return sqrt(pow(waypointGoal.x - current.x, 2) + pow(
    waypointGoal.y - current.y, 2));
}

// Get the heading error
// i.e. how many radians does the robot need 
// to turn to head towards the waypoint  
double getHeadingError() {

  double deltaX = waypointGoal.x - current.x;
  double deltaY = waypointGoal.y - current.y;
  double waypointHeading = atan2(deltaY, deltaX);
  double headingError = waypointHeading - current.theta;   
  
  // Make sure heading error falls within -PI to PI range
  if (headingError > PI) {
    headingError = headingError - (2 * PI);
  } 
  if (headingError < -PI) {
    headingError = headingError + (2 * PI);
  } 
  
  return headingError;
}

// If we haven't yet reached the goal, set the velocity value.
// Otherwise, stop the robot.
void setVelocity() {

  double distanceToWaypoint = getDistanceToWaypoint();
  double headingError = getHeadingError();

  // If we are not yet at the waypoint
  if (goToWaypoint == true && (abs(distanceToWaypoint) > distanceTolerance)) {
   
    // If the robot's heading is off, fix it.
    if (abs(headingError) > angleTolerance) {
      velCommand.linear.x = 0.0;
      velCommand.angular.z = K_a  * headingError;
    }
    // Just fix the distance gap between current pose and waypoint.
    // The magnitude of the robot's velocity is directly
    // proportional to the distance the robot is from the 
    // goal.
    else {
      velCommand.linear.x = K_l * distanceToWaypoint;
      velCommand.angular.z = 0.0;    
    }
  }
  else {
    cout << "Goal has been reached!" << endl << endl;
    velCommand.linear.x = 0.0;
    velCommand.angular.z = 0.0; 
    goToWaypoint == false;
  }
}

// This callback function updates the current position and 
// orientation of the robot. 
void updatePose(const turtlesim::PoseConstPtr &currentPose) {
  current.x = currentPose->x;
  current.y = currentPose->y;
  current.theta = currentPose->theta;
}

// This callback function updates the desired waypoint when a waypoint
// message is published to the /waypoint topic
void updateWaypoint(const geometry_msgs::Pose2D &waypointPose) {
  waypointGoal.x = waypointPose.x;
  waypointGoal.y = waypointPose.y;
  goToWaypoint = true;  
}

int main(int argc, char **argv) {

  setup();  

  // Initiate ROS
  ros::init(argc, argv, "go_to_goal_x_y");
    
  // Create the main access point to communicate with ROS
  ros::NodeHandle node;

  // Subscribe to the robot's pose
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are received that are not able to be
  // processed quickly enough.
  // Every time a new pose is received, update the robot's pose.
  ros::Subscriber currentPoseSub =
    node.subscribe("turtle1/pose", 0, updatePose);
    
  // Subscribe to the user's desired waypoint
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are received that are not able to be
  // processed quickly enough.
  // Every time a new waypoint is received, update the robot's 
  // desired waypoint.
  // The tcpNoDelay is to reduce latency between nodes and to make sure we are
  // not missing any critical waypoint messages.
  ros::Subscriber waypointPoseSub =
    node.subscribe("waypoint", 0, updateWaypoint, 
    ros::TransportHints().tcpNoDelay());

  // Publish velocity commands to a topic.
  // Hold no messages in the queue. Automatically throw away 
  // any messages that are received that are not able to be
  // processed quickly enough.
  velocityPub =
    node.advertise<geometry_msgs::Twist>("turtle1/cmd_vel", 0);

  // Specify a frequency that want the while loop below to loop at
  // In this case, we want to loop 10 cycles per second
  ros::Rate loop_rate(10); 

  // Keep running the while loop below as long as the ROS Master is active. 
  while (ros::ok()) {

    // Here is where we call the callbacks that need to be called.
    ros::spinOnce();

    // After we call the callback function to update the robot's pose, we 
    // set the velocity values for the robot.
    setVelocity();

    // Publish the velocity command to the ROS topic
    velocityPub.publish(velCommand);

    // Print the output to the console
    cout << "Current (x,y) = " << "(" << current.x << "," << current.y << ")" 
         << endl
         << "Waypoint (x,y) = " << "(" << waypointGoal.x << "," 
         << waypointGoal.y << ")" 
         << endl
         << "Distance to Waypoint = " << getDistanceToWaypoint() << " m" 
         << endl
         << "Linear Velocity (x) = " << velCommand.linear.x << " m/s" 
         << endl << endl;

    // Sleep as long as we need to to make sure that we have a frequency of
    // 10Hz
    loop_rate.sleep();
  }

  return 0;
}

Now we need to add the C++ program we just wrote to the CMakeLists.txt file.

cd ~/catkin_ws/src/go_to_goal_turtlesim
gedit CMakeLists.txt

Go to the bottom of the file.

Add the following lines.

18-add-go-to-goal-lines-x-y

Save the file, and close it.

Go to the root of the workspace.

cd ~/catkin_ws

Compile the code.

catkin_make

Launch the ROS Node

Now let’s launch the ROS node we created in the last section.

Open a new terminal window.

Start ROS.

roscore

Open another terminal window, and launch the turtlesim_node.

cd ~/catkin_ws/
rosrun turtlesim turtlesim_node

Open another terminal window, and launch the waypoint_publisher node.

rosrun go_to_goal_turtlesim waypoint_publisher

Open another terminal window, and launch the go_to_goal_x_y node.

rosrun go_to_goal_turtlesim go_to_goal_x_y

Now, go back to the terminal window where you launched the waypoint_publisher node.

Enter any waypoint x value from 0 to 11. I will enter 1.2.

Enter any waypoint y value from 0 to 11. I will enter 2.7.

When the turtle gets close enough, you will see a message that says “Goal has been reached!”

19-close-enough

Here is what the simulation looks like. You will see the robot moved from (5.544445, 5.544445) to (1.29721, 2.71791)…which is close enough to the waypoint. Once the turtle reached the waypoint, it stopped.

20-simulation-output

Let’s try another waypoint.

Go back to the terminal window where you launched the waypoint_publisher node.

Enter any waypoint x value from 0 to 11. I will enter 11.

Enter any waypoint y value from 0 to 11. I will enter 11.

Here is the output:

21-11-11-output

Create a Launch File

So that we don’t have to keep opening up ROS nodes in the future, we will create a launch file to make our life easier.

The first thing we need to do is to open a new terminal window and go to the go_to_goal_turtlesim package.

cd ~/catkin_ws/src/go_to_goal_turtlesim

Create a folder called ‘launch’.

mkdir launch

Create a new launch file inside the launch directory you just made.

cd launch

Open up the text editor.

gedit turtlesim_waypoint_follower.launch

Type the code below into the file, and save it.

<launch>
  <node pkg="turtlesim" type="turtlesim_node" name="turtlesim_node" />
  <node pkg="go_to_goal_turtlesim" type="waypoint_publisher" name="waypoint_publisher" output="screen" />
  <node pkg="go_to_goal_turtlesim" type="go_to_goal_x_y" name="go_to_goal_x_y" />
</launch>

Save this file to the catkin_ws/src/go_to_goal_turtlesim/launch folder. This file will run C++ executables.

Change the permissions of the launch file we just created.

cd ~/catkin_ws/src/go_to_goal_turtlesim/launch
sudo chmod +x turtlesim_waypoint_follower.launch

Run the launch file. Open a new terminal window, and type:

cd ~/catkin_ws/

This command below is all a single command on one line.

roslaunch go_to_goal_turtlesim turtlesim_waypoint_follower.launch

References

Credit to the book Practical Robotics in C++: Build and Program Real Autonomous Robots Using Raspberry Pi (#ad) … a fantastic book, which I highly recommend … and the official ROS tutorials for Turtlesim.

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

Visualize IMU Data Using the BNO055, ROS, and Jetson Nano

In this tutorial, we will learn how to use an NVIDIA Jetson Nano to read data from the BNO055 Absolute Orientation Sensor and connect that data to ROS using the ros_imu_bno055 package. Here is what you will be able to do by the end of this tutorial:

bno055-ros-in-action

Real-World Applications

IMUs like the BNO055 enable us to measure the acceleration and orientation of a robotic system. IMUs are common in both wheeled robots and aerial robots. 

Prerequisites

You Will Need

In addition to the parts listed in the article I linked to in the Prerequisites, you will need the following components (#ad).

Once you finish this project, you can mount the IMU on anything that moves (drone, robot car, etc.) so you can measure the system’s acceleration and orientation.

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

Soldering (Optional)

To make sure the electrical pins are stuck to the board, you can solder them like I did in this video here with the BNO055 board.

Set Up the Hardware

First, let’s set up the hardware.

Make the following connections between the BNO055 and the USB to Serial Converter:

  • Connect BNO055 Vin to 3.3V (VCC) power.
  • Connect BNO055 GND to ground (GND).
  • Connect BNO055 SDA (UART transmitter TX) to receiver RXD.
  • Connect BNO055 SCL (UART receiver RX) to transmitter TXD.
  • Connect BNO055 PS1 to BNO055 Vin (3.3V).
2021-04-19-16.38.10
2021-04-19-16.38.18-1

Now connect the other end of the USB to Serial Converter to the Jetson Nano.

2021-04-19-17.31.37

If you have a LIDAR connected to your Jetson Nano, disconnect it from the USB port.

Install and Build the BNO055 ROS Package

Let’s get all the software set up.

Turn on your Jetson Nano.

Open a new terminal window.

Install the BNO055 ROS package.

cd ~/catkin_ws/src
git clone https://github.com/RoboticArts/ros_imu_bno055.git

Build the package.

cd ~/catkin_ws/
catkin_make --only-pkg-with-deps ros_imu_bno055

Source the environment.

source devel/setup.bash

Install the ROS IMU plugin.

sudo apt-get install ros-melodic-rviz-imu-plugin

Install pyserial.

pip3 install pyserial

Install the udev rule to identify the device as ttyUSB_IMU.

roscd ros_imu_bno055
sudo cp utils/99-bno055.rules /etc/udev/rules.
sudo udevadm control --reload-rules && sudo udevadm trigger

Reboot your computer.

sudo reboot

View the IMU Data

Open a terminal window.

Install some packages.

sudo apt-get install python-catkin-pkg
sudo apt-get install python3-catkin-pkg-modules
sudo apt-get install python3-rospkg-modules

Get a list of the connected USB devices (there should only be one, which is the BNO055).

ls -la /dev/ttyUSB*

Change permissions of the USB connection.

sudo chmod 666 /dev/ttyUSB0

Open a new terminal, and type the following command to launch visualization of the IMU data in Rviz.

roslaunch ros_imu_bno055 view_imu.launch
1-run-imu-launch

Move your BNO055 around, and you will see the axes move. The red line is the x-axis, the green line is the y-axis, and the blue line is the z-axis.

2-imu_view_launch

Let’s see the active ROS topics. Open up a new terminal and type:

rostopic list

Now let’s see the data.

rostopic echo /imu/data
rostopic-echo

Press CTRL + C in all terminal windows to close everything down.

Another way to launch the BNO055 ROS driver is by using the following command. Notice how we specified the USB port name (ttyUSB0):

roslaunch ros_imu_bno055 imu.launch serial_port:=/dev/ttyUSB0

Let’s see the active ROS topics. Open up a new terminal and type:

rostopic list

Press CTRL + C in all terminal windows to close everything down.

Other Commands

Launch the IMU again.

roslaunch ros_imu_bno055 imu.launch serial_port:=/dev/ttyUSB0

Here are some other commands. To reset the IMU, you can use the following command:

rosservice call /imu/reset_device "{}"

When you type this command, your USB to Serial converter should blink a few times, and then hold steady.

To calibrate the IMU, type the following command:

roslaunch ros_imu_bno055 imu_calibration.launch serial_port:=/dev/ttyUSB0 operation_mode:=NDOF_FMC_OFF
3-calibration-mode

Move your IMU around as explained at the bottom of this page in order to calibrate the gyroscope, accelerometer, and the magnetometer.

That’s it! Keep building!