Arduino is a great development board for reading data from various sensors and controlling the robot’s DC motors. Raspberry Pi is good at running ROS on Linux. So, we can benefit from both systems to build smart robots. The easiest way is to connect these boards via USB cable and make them communicate through ROS nodes.
In this tutorial, I’ll show you how to use two Arduino boards as an extension of the Raspberry Pi computer. Before starting writing the ROS nodes, I have to set the Pi to identify each Arduino. This identification becomes necessary when the robot’s architecture is complex.
Only one ROS node can run on an Arduino board. And because I have two Arduino, I will use one to generate a random number and another to control the LED connected to pin 13.
Table of Contents
ToggleThe description of the flowchart
- The user will start all ROS nodes by running a .launch file.
- The first Arduino board will run a random number script and send data to Raspberry Pi.
- A ROS node will receive a random number from the first Arduino board. The node will run on Raspberry Pi and will command the LED on the second Arduino board.
- The second Arduino board will turn ON and OFF the LED (pin 13) depending on the commands received from the ROS node running on the Pi board.
The ROS node to generate a random number
C++
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
|
#include <ros.h>
#include <ros/time.h>
#include <std_msgs/Int32.h>
int min=1;
int max=5000;
int rand_no;
ros::NodeHandle nh;
std_msgs::Int32 rand_msg;
ros::Publisher pub_random(“/random_number”, &rand_msg);
char frameid[] = “/randomData”;
#this function returns the random number
int random_number(){
rand_no= random(min, max);
return rand_no;
}
void setup() {
nh.initNode();
nh.advertise(pub_random);
}
void loop() {
rand_msg.data=random_number();
pub_random.publish(&rand_msg);
nh.spinOnce();
delay(1000);
}
|
Testing the node
Step 1: Open a Linux Terminal and type the command:
roscore
Step 2: Open a second Linux Terminal and type the following command:
rosrun rosserial_python serial_node.py /dev/ttyACM*
Step 3: To see the random numbers generated by the Arduino node, open a third Terminal and type the following command:
rostopic echo /random_number
The ROS node that displays and calculates the LED’s stage
This ROS node in Python will run on Raspberry Pi. Before you start writing the Python code, you must create the workspace and the package that contains the node. All you need to do is in this article.
C++
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
|
#!/usr/bin/env python
import rospy
from std_msgs.msg import Int32
from std_msgs.msg import String
var=None
#define the display text
def callback(msg):
global var
var=msg.data
if __name__==‘__main__’:
rospy.init_node(‘random_LED’)
rospy.Subscriber(‘random_number’,Int32, callback)
pub=rospy.Publisher(‘LED’, String, queue_size=1)
rate=rospy.Rate(10)
while not rospy.is_shutdown():
if var<=2500:
#send message to turn OFF the LED
varP=“OFF”
rospy.loginfo(“The output is OFF and the var is: %s”, var)
else:
#send message to turn ON the LED
varP=“ON”
rospy.loginfo(“The output is ON and the var is: %s”, var)
pub.publish(varP)
rate.sleep()
|
The ROS node that controls the LED
C++
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
|
#include <ros.h>
#include <std_msgs/String.h>
ros::NodeHandle nh;
void messageCb(const std_msgs::String& msg)
{
if(msg.data ==“ON”)
digitalWrite(13, HIGH–digitalRead(13)); //blink the led
else
digitalWrite(13, LOW–digitalRead(13)); //turn off the led
}
ros::Subscriber sub(“LED”, &messageCb);
void setup()
{
pinMode(13, OUTPUT);
nh.initNode();
nh.subscribe(sub);
}
void loop()
{
nh.spinOnce();
delay(1000);
}
|
Write the launch file
<launch>
<node pkg=”rosserial_python” type=”serial_node.py” name=”twoArduino_LED” output=”screen”>
<param name=”port” value=”/dev/ttyACM0″/>
<param name=”baud” value=”57600″/>
</node>
<node pkg=”rosserial_python” type=”serial_node.py” name=”twoArduinos_RandNo” output=”screen”>
<param name=”port” value=”/dev/ttyACM1″/>
<param name=”baud” value=”57600″/>
</node>
<node name=”random_number” pkg=”pi_and_arduino” type=”twoArduinos_Pi.py” output=”screen” />
</launch>
References: