ROSSERIAL

Introduction

In the previous tutorial, we have seen the ROS Serial libraries and the installation of the required resources on your machine to work with the ROS Arduino integration.

In this tutorial, we shall see the running of the publisher and subscriber code through the Arduino board using the ROS. 

Publisher

Now, we shall look into the creation of the publisher of the hello world program. You need to compile the code in the Arduino IDE and then upload the code into the Arduino board.

Code

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

ros::NodeHandle nh;

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[13] = "hello world!";

void setup()
{
  nh.initNode();
  nh.advertise(chatter);
}

void loop()
{
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(1000);
}

Explanation of the Code

You need to import the ROS library and the standard message library to work on this code.

Later, you need to create the constructor and initiate the node, standard message and publisher method.

Next, you need to define the character array and store the hello world.

In the void setup, you need to initiate the node and chatter to publish the message.

In the void loop, the chatter will publish the hello world as the standard message with the delay of 100 milliseconds.

Subscriber

Now, we shall look into the creation of the subscriber using the rosserial library. In this, we shall blink an LED by creating the subscriber.

Code

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

ros::NodeHandle nh;

void messageCb( const std_msgs::Empty& toggle_msg){
  digitalWrite(13, HIGH-digitalRead(13));   // blink the led
}

ros::Subscriber<std_msgs::Empty> sub("toggle_led", &messageCb );

void setup()
{
  pinMode(13, OUTPUT);
  nh.initNode();
  nh.subscribe(sub);
}

void loop()
{
  nh.spinOnce();
  delay(1);
}

Explanation of the Code

Initially, we need to include the ROS library and the standard messages library. 

Then we shall mention the constructor node and declare the function to subscribe to the message and blink the LED.

The serial port communications are handled by the node.

The callback message with the subscriber will send the message to toggle the LED.

In the void setup, the ROS initiations are written to publish the messages and subscribe to any topics.

In the void loop, the ROS communications are connected using the nh.spinOnce, to connect all the callbacks to the subscriber and listen to the topic of blinking the LED on the Arduino UNO board. 

The code can be compiled and upload to the Arduino UNO board. 

Ultrasonic Sensor

Now, we shall look into the range-finding using the ultrasonic sensor, Arduino and rosserial. 

We shall control the ultrasonic sensor connected to the Arduino UNO and obtain the distance from it using the standard messages into the ROS workstation.

Code

#include <ros.h>
#include <ros/time.h>
#include <sensor_msgs/Range.h>

ros::NodeHandle  nh;

sensor_msgs::Range range_msg;
ros::Publisher pub_range( "/ultrasound_range", &range_msg);
char frameid[] = "/ultrasound";

// this constant won't change. It's the pin number of the sensor's output:
const int pingPin = 7;
const boolean CENTIMETERS = true;
const boolean INCHES = false;

void setup() {
  // initialize serial communication:
  nh.initNode();
  nh.advertise(pub_range);

  range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND;
  range_msg.header.frame_id =  frameid;
  range_msg.field_of_view = 0.1;  // fake
  range_msg.min_range = 0.002;  // 2 cm
  range_msg.max_range = 0.150;  // 150 cm

  
  //Serial.begin(9600);
}

long getRange(int pinNumber, boolean in_centimeters){

    // establish variables for the duration of the ping, and the distance result
      // in inches and centimetres:
      long duration, distance, inches, cm;
    
      // The PING))) is triggered by a HIGH pulse of 2 or more microseconds.
      // Give a short LOW pulse beforehand to ensure a clean HIGH pulse:
      pinMode(pingPin, OUTPUT);
      digitalWrite(pingPin, LOW);
      delayMicroseconds(2);
      digitalWrite(pingPin, HIGH);
      delayMicroseconds(5);
      digitalWrite(pingPin, LOW);
    
      // The same pin is used to read the signal from the PING))): a HIGH pulse
      // whose duration is the time (in microseconds) from the sending of the ping
      // to the reception of its echo off of an object.
      pinMode(pingPin, INPUT);
      duration = pulseIn(pingPin, HIGH);
    
      // convert the time into a distance
      inches = microsecondsToInches(duration);
      cm = microsecondsToCentimeters(duration);

      if (in_centimeters) 
         distance = cm;
      else 
        distance = inches;
      //Serial.print(inches);
      //Serial.print("in, ");
      Serial.print(cm);
      Serial.print("cm");
      //Serial.println();

      return distance;

  
}

void loop() {
  range_msg.range=getRange(pingPin, CENTIMETERS);
  range_msg.header.stamp = nh.now();
  pub_range.publish(&range_msg);
  nh.spinOnce();
  delay(500);
}

long microsecondsToInches(long microseconds) {
  // According to Parallax's datasheet for the PING))), there are 73.746
  // microseconds per inch (i.e. sound travels at 1130 feet per second).
  // This gives the distance travelled by the ping, outbound and return,
  // so we divide by 2 to get the distance of the obstacle.
  // See: http://www.parallax.com/dl/docs/prod/acc/28015-PING-v1.3.pdf
  return microseconds / 74 / 2;
}

long microsecondsToCentimeters(long microseconds) {
  // The speed of sound is 340 m/s or 29 microseconds per centimetre.
  // The ping travels out and back, so to find the distance of the object we
  // take half of the distance travelled.
  return microseconds / 29 / 2;
}

Explanation of the Code

The above code is completely described with the command lines clearly. It is all that the ROS publisher will send the message to the Arduino to enable the sensor to trigger and to calculate the distance. Then from Arduino, the message will be sent to subscribe to the ROS work station. The ROS workstation will subscribe to the message which contains the distance measured by the ultrasonic sensor. The publishing and subscribing of the messages are done by the ROS topic and the entire communication is supported by the rosserial.

In this way, the rosserial can be useful to work with the Arduino IDE and perform the various operations using the ROS workstation connected to the microcontroller board. For any sort of questions or doubts in this tutorial, you can reach out through the comment box.

Related Tutorial

ROS Serial Arduino

Spread knowledge

Leave a Comment

Your email address will not be published. Required fields are marked *