ROSserial86 函式库

简介

ROSserial86 是由 86Duino Coding 208 开始支援的函式库,此函式库是专为 86Duino 移植的 rosserial,用来支援 86Duino 与机器人作业系统 ROS (Robot Operating System) 之间的沟通。以下为 rosserial 的官方介绍影片:

ROSserial86 结合了 rosserial_arduinorosserial_embeddedlinux 的功能,使 86Duino 能够经由 USB Device 接口、串列埠、网路来收送 ROS 讯息。使用此函式库,便可将 86Duino 视为一完整且成熟的 ROS 节点,能够直接的发布、订阅 ROS 话题(ROS Topics),亦可以提供或请求 ROS 服务(ROS Services)、发布 TF 变换、取得 ROS 系统时间。

因为 ROSserial86 相容于 rosserial,使用者可以参考 rosserial 官方维基文件来学习 ROSserial86 的使用。ROSserial86 在使用上与 rosserial 唯一的不同,在于 ROSserial86 允许在节点初始化时选择不同的连接方式,下面我们简单示例说明选择连接 ROS 方式的方法。

说明与范例

经由 USB Device 接口连接 ROS

若是使用 86Duino 上的 USB Device 接口来连线,使用方式与 rosserial_arduino 一模一样,在呼叫 initNode() 初始化节点时不需要传任何参数。范例程式码如下:

#include <ros.h>  //引入 rosserial 标头档
#include <std_msgs/String.h>  //引入 rosserial 讯息定义

//宣告一个节点处理者来实现与 ROS 之间的沟通
ros::NodeHandle nh;
//宣告一个 std_msgs::String 型别的讯息
std_msgs::String str_msg; 
//宣告一个发布者来发布讯息,将讯息发布到 chatter 话题
ros::Publisher chatter("chatter", &str_msg);

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

void setup()
{
    nh.initNode();  //初始化节点,使用 USB 传输的方式来沟通
    nh.advertise(chatter);  //让节点能够藉由发布者来发布讯息
}

void loop()
{
    str_msg.data = hello;  //将讯息的资料填入 hello 字元阵列的内容
    chatter.publish( &str_msg );  //发布 str_msg 到话题 chatter
    nh.spinOnce();  //让节点去处理 callback 函式
    delay(1000);
}

硬体连接方式:直接将 86Duino 透过 USB Device 接口连接到正在跑 rosserial server(例如 rosserial_python)的 host 主机即可,如下图示例:

1

经由串列埠连接 ROS

使用串列埠来进行连线,只需要在呼叫 initNode() 初始化节点时,传入指定的串列埠做为参数即可,如nh.initNode("/Serial1"),目前所支援的串列埠参数为 /Serial1、/Serial2、/Serial3。串列埠鲍率可以在初始化前呼叫 nh.getHardware()->setBaud(baudrate) 来设定,预设的鲍率是 57600。范例程式码如下:

#include <ros.h>  //引入 rosserial 标头档
#include <std_msgs/String.h>  //引入 rosserial 讯息定义

//宣告一个节点处理者来实现与 ROS 之间的沟通
ros::NodeHandle nh;
//宣告一个 std_msgs::String 型别的讯息
std_msgs::String str_msg; 
//宣告一个发布者来发布讯息,将讯息发布到 chatter 话题
ros::Publisher chatter("chatter", &str_msg);

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

void setup()
{
    nh.getHardware()->setBaud(57600);  //设定 baudrate
    nh.initNode("/Serial1");  //初始化节点,使用 Serial1 来连接 ROS
    nh.advertise(chatter);  //让节点能够藉由发布者来发布讯息
}

void loop()
{
    str_msg.data = hello;  //将讯息的资料填入 hello 字元阵列的内容
    chatter.publish( &str_msg );  //发布 str_msg 到话题 chatter
    nh.spinOnce();  //让节点去处理 callback 函式
    delay(1000);
}

硬体连接方式:在此范例中我们用 RoBoard RB-100,在其上跑 rosserial server(例如 rosserial_python)做为 ROS 主机端,86Duino 做为 rosserial 客户端,透过 Serial1 与 RoBoard 的 COM3 连接(86Duino 的 TX 线接 RoBoard 的 RX 线,86Duino 的 RX 线接 RoBoard 的 TX 线,地线对接),如下所示:

4

全貌如下:

2-1

经由网路连接 ROS

使用网路连线,需先呼叫 Ethernet 函式库 设定 86Duino 的 IP 位址,之后在呼叫 initNode() 初始化节点时,传入 ROS 主机的 IP 位址即可,使用方式与 rosserial_embeddedlinux 相同。范例程式码如下:

#include <ros.h>  //引入 rosserial 标头档
#include <std_msgs/String.h>  //引入 rosserial 讯息定义

#include <Ethernet.h> //引入 Ethernet 函式库标头档

//宣告一个节点处理者来实现与 ROS 之间的沟通
ros::NodeHandle nh;
//宣告一个 std_msgs::String 型别的讯息
std_msgs::String str_msg; 
//宣告一个发布者来发布讯息,将讯息发布到 chatter 话题
ros::Publisher chatter("chatter", &str_msg);

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

void setup()
{
    IPAddress ip(192,168,0,2);
    Ethernet.begin(NULL, ip);  //初始化网路设定

    nh.initNode("192.168.0.1");  //初始化节点,连线到位于 192.168.0.1 的 ROS 主机
    nh.advertise(chatter);  //让节点能够藉由发布者来发布讯息
}

void loop()
{
    str_msg.data = hello;  //将讯息的资料填入 hello 字元阵列的内容
    chatter.publish( &str_msg );  //发布 str_msg 到话题 chatter
    nh.spinOnce();  //让节点去处理 callback 函式
    delay(1000);
}

硬体连接方式:直接将 86Duino 连接到 Ethernet 网路孔即可,下图示范 ROS 主机与 86Duino 直接以网路线对接的连接方式:

3

86Duino 透过网路发佈类比採样资讯到 ROS 主题(ROS Topic)的范例程式:

#include <Arduino.h>

#include <ros.h>  //引入 rosserial 标头档
#include <std_msgs/String.h>  //引入 rosserial 讯息定义

#include <Ethernet.h> //引入 Ethernet 函式库标头档

//宣告一个节点处理者来实现与 ROS 之间的沟通
ros::NodeHandle nh;

//宣告一个 rosserial_arduino::Adc adc_msg 型别的讯息
rosserial_arduino::Adc adc_msg;
//宣告一个发布者来发布讯息,将讯息发布到 adc 话题
ros::Publisher p("adc", &adc_msg);

void setup()
{
    pinMode(13, OUTPUT);
    IPAddress ip(192,168,0,2);
    Ethernet.begin(NULL, ip);  //初始化网路设定

    nh.initNode("192.168.0.1");  //初始化节点,连线到位于 192.168.0.1 的 ROS 主机
    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()
{
    //将 86Duino 类比输入接口採样到的值填入 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);  //发布 adc_msg 到话题 adc

    nh.spinOnce();  //让节点去处理 callback 函式
    delay(10);
}

经由 ESP8266 WiFi 模组连接 ROS

使用 ESP8266 WiFi 模组来透过无线网路进行连线,要在呼叫 initNode() 之前先使用 setESP8266(HardwareSerial, Baudrate)setWiFi("SSID", "PASSWORD") 来设定 WiFi 连线。之后在呼叫 initNode() 初始化节点时,传入 ROS 主机的 IP 位址即可。范例程式码如下:

#include <ros.h> //引入 rosserial 标头档
#include <std_msgs/String.h> //引入 rosserial 讯息定义

//宣告一个节点处理者来实现与 ROS 之间的沟通
ros::NodeHandle nh;

//宣告一个 std_msgs::String 型别的讯息
std_msgs::String str_msg; 
//宣告一个发布者来发布讯息,将讯息发布到 chatter 话题
ros::Publisher chatter("chatter", &str_msg);

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

void setup()
{
  nh.getHardware()->setESP8266(Serial1, 115200); //设定 ESP8266 连接到的 86Duino 串列埠与鲍率
  nh.getHardware()->setWiFi("SSID", "PASSWORD"); //设定所欲连接的 WiFi AP 之 SSID 与密码
  nh.initNode("192.168.0.1"); //初始化节点,连线到位于 192.168.0.1 的 ROS 主机
  nh.advertise(chatter);  //让节点能够藉由发布者来发布讯息
}

void loop()
{  
  str_msg.data = hello; //将讯息的资料填入 hello 字元阵列的内容
  chatter.publish( &str_msg ); //发布 str_msg 到话题 chatter
  nh.spinOnce(); //让节点去处理 callback 函式
  delay(1000);
}

硬体连接方式:在此范例中我们要将 ESP8266 之 VCC 与 CH_PD 都接在 86Duino 的 3.3V,并将 ESP8266 与 86Duino Serial1 连接,即 UTXD 接至 86Duino 的 RX1,URXD 接至 TX1。

下图为 ESP8266 WiFi 模组的接脚名称:

3

参照上图,ESP8266 WiFi 模组与 86Duino 的连接方法如下表所示:

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)

将笔记型电脑做为 rosserial 主机端,86Duino 做为 rosserial 客户端,连线至同样的 WiFi 基地台来进行连线,完成的全貌如下:
3


函式库参考主页面

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.