ROSserial86 Library

Introduction

ROSserial86 is a library that is supported by the 86Duino Coding 208 IDE and is a rosserial designed for the 86Duino port to support communication between the 86Duino and the Robot Operating System (ROS). The following is an official introduction to rosserial:

ROSserial86 combines the functions of rosserial_arduino and rosserial_embeddedlinux so that the 86Duino can send and receive ROS messages via USB Device interface, serial port, and network. By using this library, the 86Duino can be seen as a complete and mature ROS node. It can be directly published, subscribe to ROS Topics, and can also provide or request ROS services, as well as release TF conversion and get the ROS system time.

Because the ROSserial86 is compatible with rosserial, users can refer to the rosserial official wiki to learn how to use ROSserial86. In using ROSserial86 and rosserial, the only difference is that ROSserial86 allows the node to initialize the choice of different ways to connect; the following illustrates the steps to choosing how to connect to the ROS.

Illustration and Sample

Connect ROS by USB Device

If you use the USB Device interface on the 86Duino to connect to the rosserial_arduino, you do not need to pass any parameters when calling initNode() to initialize the node. The sample code is as follows:

#include <ros.h>  // Introduce rosserial header file
#include <std_msgs/String.h>  // Introduce rosserial message definitions

// Declare a node handler to communicate with ROS
ros::NodeHandle nh;
// Declare a std_msgs :: String message
std_msgs::String str_msg; 
// Declare a publisher to post a message and post the message to the chatter topic
ros::Publisher chatter("chatter", &str_msg);

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

void setup()
{
    nh.initNode();  // Initialize the node, using USB to communicate 
	// Let the node be able to publish the message by the publisher
    nh.advertise(chatter);
}

void loop()
{
    str_msg.data = hello;  // Fill the contents of the message with hello 
    chatter.publish( &str_msg );  // Release str_msg to topic chatter
    nh.spinOnce();  // Let the node handle the callback function
    delay(1000);
}

Hardware connection: The 86Duino connects directly with the USB Device to the host that runs the rosserial server (such as rosserial_python), as shown in the following example:

1

Connect ROS by Serial Port

Use the serial port to connect and call initNode() initialization node, the incoming serial port as a parameter, such as nh.initNode("/Serial1"), the current support of the parameters are “/ Serial1”, “/ Serial2”, “/ Serial3”. The serial baud rate can be set by calling nh.getHardware()->setBaud(baudrate) before initialization. The default baud rate is 57600. The sample code is as follows:

#include <ros.h>  // Introduce rosserial header file
#include <std_msgs/String.h>  // Introduce rosserial message definitions
 
// Declare a node handler to communicate with ROS
ros::NodeHandle nh;
// Declare a std_msgs :: String message
std_msgs::String str_msg; 
// Declare a publisher to post a message and post the message to the chatter topic
ros::Publisher chatter("chatter", &str_msg);
 
char hello[13] = "hello world!";
 
void setup()
{
    nh.getHardware()->setBaud(57600);  // Set baudrate
    nh.initNode("/Serial1");  // Initialize the node, use Serial1 to connect ROS
	// Let the node be able to publish the message by the publisher
    nh.advertise(chatter);  
}
 
void loop()
{
	// Fill the contents of the message with the contents of the hello character array
    str_msg.data = hello;  
    chatter.publish( &str_msg );  // Release str_msg to topic chatter
    nh.spinOnce();  // Let the node handle the callback function
    delay(1000);
}

Hardware connection: In this example, we use the RoBoard RB-100, running a rosserial server (such as rosserial_python) as the ROS host, the 86Duino as client, and connected through Serial1 and RoBoard COM3 connection (86Duino TX Line connects to RoBoard RX line, 86Duino RX line connects to RoBoard TX line, ground docking).

4

2-1

Connect ROS by Internet

Use the network connection, you need to call the Ethernet library to set up the IP address of the 86Duino, call initNode() initialization node, enter the ROS host IP address, and then the ROS can be used in the same way as rosserial_embeddedlinux. The sample code is as follows:

#include <ros.h>  // Introduce rosserial header file
#include <std_msgs/String.h>  // Introduce rosserial message definitions
 
#include <Ethernet.h> // Introduces the Ethernet library header file
 
// Declare a node handler to communicate with ROS
ros::NodeHandle nh;
// Declare a std_msgs :: String message
std_msgs::String str_msg; 
// Declare a publisher to post a message and post the message to the chatter topic
ros::Publisher chatter("chatter", &str_msg);
 
char hello[13] = "hello world!";
 
void setup()
{
    IPAddress ip(192,168,0,2);
    Ethernet.begin(NULL, ip);  //initialize the network settings
 
	//initialize the node, connect to the ROS host at 192.168.0.1
    nh.initNode("192.168.0.1");
	//let the node be able to publish the message by the publisher	
    nh.advertise(chatter);  
}
 
void loop()
{
	//fill the contents of the message with the contents of the hello character array
    str_msg.data = hello;  
    chatter.publish( &str_msg );  //release str_msg to topic chatter
    nh.spinOnce();  //Let the node handle the callback function
    delay(1000);
}

Hardware connection: Ethernet is directly connected to the 86Duino.

3

The following is an example code for sampling information to ROS through network release analog with the 86Duino:

#include <Arduino.h>
 
#include <ros.h>  // Introduce rosserial header file
#include <std_msgs/String.h>  // Introduce rosserial message definitions
 
#include <Ethernet.h> // Introduces the Ethernet library header file
 
// Declare a node handler to communicate with ROS
ros::NodeHandle nh;
 
// Declare a rosserial_arduino :: Adc adc_msg type message
rosserial_arduino::Adc adc_msg;
// Declare a publisher to post a message and post the message to an adc topic
ros::Publisher p("adc", &adc_msg);
 
void setup()
{
    pinMode(13, OUTPUT);
    IPAddress ip(192,168,0,2);
    Ethernet.begin(NULL, ip);  // Initialize the internet settings
 
	// Initialize the node, connect to the ROS host at 192.168.0.1
    nh.initNode("192.168.0.1");  
	// let the node be able to publish the message by the publisher
    nh.advertise(p);  
}
 
int averageAnalog(int pin) {
    int v = 0;
    for (int i = 0; i < 4; i++) v += analogRead(pin);
    return v / 4;
}
 
long adc_timer;
 
void loop()
{
    // Put the value of the 86Duino analog input interface into adc_msg
    adc_msg.adc0 = averageAnalog(0);
    adc_msg.adc1 = averageAnalog(1);
    adc_msg.adc2 = averageAnalog(2);
    adc_msg.adc3 = averageAnalog(3);
    adc_msg.adc4 = averageAnalog(4);
    adc_msg.adc5 = averageAnalog(5);
 
    p.publish(&adc_msg);  // Release adc_msg to topic adc
 
    nh.spinOnce();  // Let the node handle the callback function
    delay(10);
}

Connect ROS by ESP8266 WiFi

Use the ESP8266 WiFi module to connect via the wireless network. Set the WiFi connection by using setESP8266(HardwareSerial, Baudrate) and setWiFi("SSID", "PASSWORD") before calling initNode(). After calling initNode() initialization node, enter the ROS host IP address. The sample code is as follows:

#include <ros.h> // Introduce rosserial header file
#include <std_msgs/String.h> // Introduce rosserial message definitions
 
// Declare a node handler to communicate with ROS
ros::NodeHandle nh;
 
// Declare a std_msgs :: String message
std_msgs::String str_msg; 
// Declare a publisher to post a message and post the message to the chatter topic
ros::Publisher chatter("chatter", &str_msg);
 
char hello[13] = "hello world!";
 
void setup()
{
  // set the ESP8266 to the 86Duino serial port and the baud rate
  nh.getHardware()->setESP8266(Serial1, 115200); 
  // Set the SSID and password for the WiFi AP that you want to connect to.
  nh.getHardware()->setWiFi("SSID", "PASSWORD"); 
  // initialize the node, connect to the ROS host at 192.168.0.1
  nh.initNode("192.168.0.1");
  // Let the node be able to publish the message by the publisher  
  nh.advertise(chatter);  
}
 
void loop()
{  
  // Fill the contents of the message with the contents of the hello character array
  str_msg.data = hello; 
  chatter.publish( &str_msg ); // release str_msg to topic chatter
  nh.spinOnce(); // Let the node handle the callback function
  delay(1000);
}

Hardware connection: In this example, we need to connect ESP8266 VCC and CH_PD to the 3.3V of the 86Duino. Then connect the ESP8266 to 86Duino Serial1 (UTXD connected to 86Duino RX1, URXD connected to TX1).

The figure below shows the pin assignment for the ESP8266 WiFi module:

3

Refer to the figure above. The connection of ESP8266 WiFi module and the 86Duino is shown in the following table:

Pins of ESP8266 Pins of 86Duino Notes
UTXD RX1 (Serial1: 86Duino PIN 0)
CH_PD 3.3V Boot mode – must be 3.3v to enable WiFi
RST N/C
VCC 3.3V
GND GND
GPIO0 N/C
GPIO2 N/C
URXD TX1 (Serial1: 86Duino PIN 1)

Designate the computer as the rosserial host side, 86Duino as rosserial client, and connect them to the same WiFi base station, the whole picture is as follows:
3


Libraries Reference Home

The text of the 86Duino reference is a modification of the Arduino reference, and is licensed under a Creative Commons Attribution-ShareAlike 3.0 License. Code samples in the reference are released into the public domain.