How to Control Arduino With ROS

by Robottronic in Circuits > Arduino

10497 Views, 4 Favorites, 0 Comments

How to Control Arduino With ROS

0_ROS and an Arduino.png

If you don't have ROS installed on your PC see instructions on how to install it:

https://www.instructables.com/How-to-Install-ROS/

Supplies

  • Arduino UNO (or any other Arduino)
  • Red and Blue LED
  • 3x Jumper Wires

Wiring the Example

1_ROS and an Arduino.png
2_ROS and an Arduino.png
3_ROS and an Arduino.png
4_ROS and an Arduino.png

We are going to prepare our Arduino for the code coming in the next steps. To connect the board simply click on the images above and slide one by one and follow them step by step.

  1. First make sure that the both LEDs are turned as shown. The short Lead should be in the same column of the breadboard. [Image 1]
  2. We are going to connect the grounds of both LEDs and the Arduino with a single Jumper Wire as shown. [Image 2]
  3. Connect the digital pin D13 with the long lead of the red LED. [mage 3]
  4. Connect the digital pin D12 with the long lead of the blue LED. [Image 4]

With the wiring is ready, we are prepared to plug in the Arduino and start with the programming.

The Code

1. Open the Arduino IDE

2. Copy this code:

#include <ros.h>
#include <std_msgs/Empty.h>
#include <std_msgs/String.h>

ros::NodeHandle  nh;

std_msgs::String OurLedState;
ros::Publisher LEDstate("state", &OurLedState);

char RedState[20] = "The Red LED blinks!";
char BlueState[21] = "The Blue LED Blinks!";

void RedOne( const std_msgs::Empty& toggle_msg) 
{  
digitalWrite(13, HIGH);
delay(3000); 
digitalWrite(13, LOW);
OurLedState.data = RedState;
} 

void BlueOne( const std_msgs::Empty& toggle_msg) 
{  
digitalWrite(12, HIGH);
delay(3000); 
digitalWrite(12, LOW);
OurLedState.data = BlueState;
} 

ros::Subscriber<std_msgs::Empty> RedLED("red", &RedOne ); 
ros::Subscriber<std_msgs::Empty> BlueLED("blue", &BlueOne ); 

void setup()  
{ 
pinMode(13, OUTPUT);
pinMode(12, OUTPUT); 
nh.initNode(); 
nh.subscribe(RedLED);
nh.subscribe(BlueLED);
nh.advertise(LEDstate);
} 

void loop()  
{  
LEDstate.publish( &OurLedState );
nh.spinOnce();  
delay(1);  
}

The Code Explained

#include <ros.h>
#include <std_msgs/Empty.h>
#include <std_msg/String.h>
  • As a part of every ROS Arduino program, you need to include the ros.h header file and header files for any messages that you will be using, here we are using a standard message Empty and String.
ros::NodeHandle nh;
  • We need to instantiate the node handle; node handle allows our program to create publishers and subscribers. Also it takes care of serial port communications. "nh" is just the name I gave this NodeHandle, you can put here anything you want.
std_msgs::String OurLedState;
ros::Publisher LEDstate("state", &OurLedState);
  • std_msgs contains wrappers for ROS message types. In our case it's string type.
  • "OurLedState" is basically the name of our String, you can name it however you want.

  • This part of code is referred to the Publisher. When we want to find out which light is on we will call our "state" and we will get feedback.
char RedState[20] = "The Red LED blinks!";
char BlueState[21] = "The Blue LED blinks!";
  • We need to set the text which will be shown when we call out our "state"
  • In square brackets we put the number of characters (char) we are using. Keep in mind that you'll need to include spaces too and one "null char"
  • Generally, strings are terminated with a null character (ASCII code 0). This allows functions to tell where the end of a string is.
void RedOne( const std_msgs::Empty& toggle_msg) 
{  
  digitalWrite(13, HIGH);
  delay(3000); 
  digitalWrite(13, LOW);
  OurLedState.data = RedState;
} 
  • We create the callback function for our subscriber.
  • The callback function must take a constant reference of a message as its argument.
  • In our callback named RedOne, the type of message is std_msgs::Empty and the message name will be toggle_msg.
  • Inside the void RedOne is default Arduino code for turning LED on, delaying it for 3 seconds and then turning it off.
  • Number inside brackets is our digital pin where red LED is connected.
  • The last line in this part of code is referred to message that will be published when red LED blinks.
void BlueOne( const std_msgs::Empty& toggle_msg) 
{  
  digitalWrite(12, HIGH);
  delay(3000); 
  digitalWrite(12, LOW);
  OurLedState.data = BlueState;
} 
  • This part of code is the same as upper one, but this is code for blue LED.
ros::Subscriber<std_msgs::Empty> RedLED("red", &RedOne );
ros::Subscriber<std_msgs::Empty> BlueLED("blue", &BlueOne );
  • We instantiate a Subscriber with a topic name of "RedLED" (and "BlueLED") and type std_msgs::Empty.
  • We will call the topic(s) in the Terminal by calling arguments from brackets. In our case when we want to blink the red LED we will call "red", otherwise we will call "blue".
  • Part with & sign is referred to our void RedOne() and void BlueOne()
  • With Subscribers, you must remember to template the subscriber upon the message. Its two arguments are the topic it will be subscribing to and the callback function it will be using.
void setup()
{ 
   pinMode(13, OUTPUT);
   pinMode(12, OUTPUT);
   nh.initNode();
   nh.subscribe(RedLED);
   nh.subscribe(BlueLED);
   nh.advertise(LEDstate);
}
  • In the Arduino setup function you then need to initialize your ROS node handle (named "nh"), advertise any topics being published, and subscribe to any topics you wish to "listen" to.
  • the arguments in the brackets are the names of parts to which subscribe or advertise refers.
void loop()
{  
  LEDstate.publish( &OurLedState )
  nh.spinOnce();
  delay(1);
}
  • In the Arduino loop function ros::spinOnce() will handle passing messages to the subscriber callback.
  • ROS only processes your callbacks when you tell it to with .spinOnce()

  • LEDstate.publish( &OurLedState ) needs to be in the loop so it can constantly receive messages which LED is on.

Uploading the Code

1. In your VirtualBox tab select Devices > USB > Select Your Arduino Serial Port

2. To upload the code to your Arduino, use the upload function within the Arduino IDE. This is no different from uploading any other sketch.

GOOD TO KNOW: Sometimes there is a trouble with uploading the code to Arduino because of VirtualBox and maybe you'll be getting error saying:

“avrdude: ser_open(): can't open device ”/dev/ttyACM0“: Permission denied”

Here is a solution to that error:

1. To confirm the port exists enter the following from the root directory.

ls /dev/ttyUSB0 

2. To set read/write permissions, enter the following

sudo chmod a+rw /dev/ttyUSB0 
  • Your port maybe wont be USB0, yet e.g. USB1 or 2 or something else.

Here is ANOTHER solution to that error:

  • Scroll down to: Set Up the Serial Port for VirtualBox With Ubuntu

https://automaticaddison.com/how-to-connect-arduino-to-ros/

Running the Code

blnk.PNG

1. Open Terminal Window and launch the roscore:

roscore

2. Open another Terminal and run the rosserial client application that forwards your Arduino message to the rest of ROS (make sure to use the correct serial port):

rosrun rosserial_python serial_node.py /dev/ttyUSB0

3. Again open one more Terminal and you can toggle the LED using rostopic:

rostopic pub red std_msgs/Empty -1
rostopic pub blue std_msgs/Empty -1
  • -1 or --once enables once mode.
  • If you don't want to have to stop rostopic with ctrl-C, you can publish in once mode. rostopic will keep the message latched for 3 seconds, then quit.

4. Once more open another Terminal and "listen" the message which LED is on:

rostopic echo state
  • rostopic echo prints messages to screen.