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.