A few weeks ago I started writing a series of tutorials that ease the work of beginners in ROS. The first tutorial was about a template for a publisher node, the second tutorial was about a template for a subscriber node in ROS, and the third tutorial was a simple ROS subscriber and publisher in Python.
Today, I continue the series of tutorials with a template for a ROS publisher using rosserial on the Arduino board. In addition, I’ll test the template and write a publisher node.
Below you will find the template for a ROS publisher using rosserial on the Arduino board. To write your own publisher using rosserial on Arduino, copy the template into Arduino IDE, delete the information that you don’t need and replace the text in capital letters.
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
|
#Template for a ROS Publisher Using rosserial on Arduino
//different specific libraries
#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>
#include <std_msgs/Float32.h>
#include “DHT.h”
//create the ros node nh. The node will be used to publish to Arduino
ros::NodeHandle nh;
//for example, if you’re using an ultrasonic sensor, the sensor message is Range
sensor_msgs::SENSOR_RETURN_TYPE msg;
ros::Publisher pub(“/TOPIC_NAME”, &msg);
void setup() {
  nh.initNode();
  nh.advertise(pub);
}
void loop() {
  unsigned long currentMillis = millis();
  if (currentMillis–range_timer >= 50) //publish every 50 milliseconds
  {
    range_timer = currentMillis+50;
    pub.publish(&msg);
    }
 Â
  nh.spinOnce();
}
|
I used the above template to write a ROS node that will advertise the distance to an object detected by an ultrasonic sensor.
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
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
|
#include “NewPing.h” //ultrasonic sensor specific library
#include <ros.h>
#include <sensor_msgs/Range.h>
//define the pins
#define trigPin 5
#define echoPin 4
//define the constants
#define maxDistance 400
#define intervalR 200
NewPing sonar(trigPin, echoPin, maxDistance);
//variables
float range;
unsigned long range_timer;
float duration, distance;
ros::NodeHandle nh;
sensor_msgs::Range range_msg;
ros::Publisher pub_range_ultrasound(“/ultrasound”, &range_msg);
float returnDistance()
{
  digitalWrite(trigPin, LOW);
  delayMicroseconds(2);
  digitalWrite(trigPin, HIGH);
  delayMicroseconds(10);
  digitalWrite(trigPin, LOW);
  duration = pulseIn(echoPin, HIGH);
  // convert the time into a distance
  return duration/58; //    duration/29/2, return centimeters
}
void setup() {
    //pin mode for the ultrasonic sensor
  pinMode(trigPin, OUTPUT);
  pinMode(echoPin, INPUT);
  nh.initNode();
  nh.advertise(pub_range_ultrasound);
}
void loop() {
  unsigned long currentMillis = millis();
  if (currentMillis–range_timer >= intervalR)
  {
    range_timer = currentMillis+intervalR;
 Â
    range_msg.range = returnDistance();
    pub_range_ultrasound.publish(&range_msg);
    }
 Â
  nh.spinOnce();
}
|
How to run the node
Step 1: Open a new Terminal, type roscore and press the Enter key
Step 2: Open another Terminal and type the following command:
C++
1
|
rosrun rosserial_python serial_node.py /dev/ttyACM0
|
Step 3: To verify the node’s output, open a new Terminal and type the following command:
C++
1
|
rostopic echo ultrasound
|