ROS中rosserial通訊協議初探


ROS中rosserial通訊協議初探

串行的通訊,我們用串口模擬下通訊圖

 

官方

http://wiki.ros.org/rosserial
rosserial
 

1概述


標準ROS序列化message的協議,可以讓一個字符設備(單片機)通過串口或者網口就能實現多topics和services的功能。
1.1客戶端庫很多
1.2ROS端可以python也可以c++
1.3舉例


2限制

2.1Message 最大size ,發佈和訂閱數量
AVR Model | Input/Output buffer sizes | Publishers/Subscribers

ATMEGA168 | 150/150 bytes | 6/6
ATMEGA328P | 280/280 bytes | 25/25
All others | 512/512 bytes | 25/25
可以自定義大小
2.2~2.4
float string array的數類型

3協議

協議就是在往串口發送的數據的基礎上加上包頭包尾,
並允許多個topics同時共享一個串口

3.1Packet Format

  1st Byte - Sync Flag (Value: 0xff)
  2nd Byte - Sync Flag / Protocol version  0xff on ROS Groovy, 0xfe on ROS Hydro, Indigo, and Jade.
  3rd Byte - Message Length (N) - Low Byte
  4th Byte - Message Length (N) - High Byte
  5th Byte - Checksum over message length
  6th Byte - Topic ID - Low Byte
  7th Byte - Topic ID - High Byte
  x Bytes  - Serialized Message Data
  Byte x+1 - Checksum over Topic ID and Message Data

橫過來看
起始1  /  版本號1  /  內容長度L、H 2  /  內容長度校驗1  / Topic ID L、H 2  /  內容x  /   內容校驗1

校驗算法
 

Message Length Checksum = 255 - ((Message Length High Byte + 
                                   Message Length Low Byte) % 256 )

Message Data Checksum = 255 - ((Topic ID Low Byte +
                                Topic ID High Byte + 
                                Data byte values) % 256)

由此校驗算法上可見 Topic ID兩個字節是作爲校驗數據的一部分,數據包長度這兩個字節不算在內。


說Topics ID 0-100 系統保留 

http://docs.ros.org/api/rosserial_msgs/html/msg/TopicInfo.html

uint16 ID_PUBLISHER=0
uint16 ID_SUBSCRIBER=1
uint16 ID_SERVICE_SERVER=2
uint16 ID_SERVICE_CLIENT=4
uint16 ID_PARAMETER_REQUEST=6
uint16 ID_LOG=7
uint16 ID_TIME=10
uint16 ID_TX_STOP=11
uint16 topic_id
string topic_name
string message_type
string md5sum
int32 buffer_size

此處的Topic ID的稱謂值得注意,我覺得理解爲 Topic類別ID 更好,他區分了這個數據包話題是發佈、訂閱或service服務端客戶端等等

3.2話題協商 Topic Negotiation

在開始數據傳輸之前,上位機必須向嵌入式設備查詢將要發佈或訂閱的主題的名稱和類型。
主題協商包括對主題的查詢、對主題數量的響應以及定義每個主題的數據包。對主題的請求使用主題ID 0。


主題請求時 Topic ID設置0

開始/版本號/長度/長度校驗/Topic ID/內容校驗

0xFF/0xFE/0x00/0x00/0xFF/0x00/0x00/0xFF

會話結束 topic_id = ID_TX_STOP=11(0x0B)

開始/版本號/長度/長度校驗/Topic ID/內容校驗

0xFF/0xFE/0x00/0x00/0xFF/0x0B/0x00/0xE3

上位機發過來的時鐘/同步幀,(ID_TIME=10)
0xFF/0xFE/0x08/0x00/CHK/0x0A/0x00/8個bytes/CHK


當上位機發送主題請求後
0xff 0xfe 0x00 0x00 0xff 0x00 0x00 0xff
下位機應該發送
一系列響應包(消息類型rosserial-msgs/TopicInfo,每個包都包含有關特定主題的信息,用以下數據代替序列化的消息:

uint16 topic_id
  string topic_name
  string message_type
  string md5sum
  int32 buffer_size
注意這裏又有一個topic_id,這個topic_id是運行程序中類實例的id,不能與 Topic ID混淆。
這五個數據合在一起是數據包的內容部分。

用單片機實現一個publisher,下面是實驗數據分析

[20:46:35.143]發→◇FF FE 00 00 FF 00 00 FF □
[20:46:35.399]收←◆
FF FE 08 00 F7 
0A 00 ----------------------------0x000A=Topic ID  (ID_TIME=10)
00 00 00 00 00 00 00 00 
F5 --------------------------------0xf5包校驗0xff-((0x0A+0x00+0+0+0+0+0+0+0+0)%0x100)


FF FE 48 00 B7 -------------------0x0048=72 包數據長度 0xb7=0xff-((0x48+0x00)%0x100)
00 00 -----------------------------0x0000= Topic ID(ID_PUBLISHER=0)
7D 00 -----------------------------0x7D=125 topic_id (publisher ID)
07 00 00 00 ----------------------0x0007=7,數據長度 topic_name="chatter"
63 68 61 74 74 65 72 
0F 00 00 00 ----------------------0x000f=15,數據長度 message_type ="std_msgs/String"
73 74 64 5F 6D 73 67 73 2F 53 
74 72 69 6E 67 
20 00 00 00 ----------------------0x0020=32,數據長度 md5sum="992ce8a1687cec8c8bd883ec73ca41d1"
39 39 32 63 65 38 61 31 36 38 
37 63 65 63 38 63 38 62 64 38 
38 33 65 63 37 33 63 61 34 31 
64 31 
18 01 00 00 ----------------------0x0118=280,是atmage328p的buffer_size  (看2.1)
0C --------------------------------0x0C 包校驗

[20:46:36.404]收←◆
FF FE 10 00 EF 
7D 00 
0C 00 00 00 
68 65 6C 6C 6F 20 77 6F 72 6C 64 21 
F9 

[20:46:37.404]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:38.404]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 

FF FE 08 00 F7 
0A 00 
00 00 00 00 00 00 00 00 F5 

[20:46:39.402]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:40.403]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:41.402]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 FF FE 08 00 F7 0A 00 00 00 00 00 00 00 00 00 F5 
[20:46:42.402]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:43.401]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:44.401]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 FF FE 08 00 F7 0A 00 00 00 00 00 00 00 00 00 F5 
[20:46:45.401]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 
[20:46:46.400]收←◆FF FE 10 00 EF 7D 00 0C 00 00 00 68 65 6C 6C 6F 20 77 6F 72 6C 64 21 F9 

上個標記好的圖吧

 

消息類型MD5的對應舉例

https://github.com/frankjoshua/rosserial_arduino_lib/blob/master/src/std_msgs/Byte.h

"std_msgs/Byte"
MD5("byte data")="ad736a2e8818154c487bb80fe42ce43b"
"std_msgs/Bool"
MD5("bool data")="8b94c1b53db61fb6aed406028ad6332a"
"std_msgs/String"
MD5("string data")="992ce8a1687cec8c8bd883ec73ca41d1"


關於publisher的ID
https://github.com/frankjoshua/rosserial_arduino_lib/blob/master/src/ros/node_handle.h

void negotiateTopics()
      {
        rosserial_msgs::TopicInfo ti;
        int i;
    
        for(i = 0; i < MAX_PUBLISHERS; i++)
        {
          if(publishers[i] != 0) // non-empty slot
          {
        ReadBuffer buffer;
        
        ti.topic_id = publishers[i]->id_;
        ti.topic_name = (char *) buffer.readTopicName( publishers[i] );
        ti.message_type = (char *) buffer.readMsgInfo( publishers[i]->msg_->getType() );
        ti.md5sum = (char *) buffer.readMsgInfo( publishers[i]->msg_->getMD5() );
        ti.buffer_size = OUTPUT_SIZE;
        publish( publishers[i]->getEndpointType(), &ti );
....

3.3時間

通過向每個方向發送std_msg::Time來處理時間同步。嵌入式設備可以通過發送空時間消息從PC/平板電腦請求當前時間。返回的時間用於查找時鐘偏移量。

4 Report a Bug

 

 

 

arduino測試源碼


#include <ros.h>
#include <std_msgs/String.h>
#include <std_msgs/UInt16.h>
ros::NodeHandle  nh;

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);
std_msgs::String str_msg2;
ros::Publisher chatter2("chatter2", &str_msg2);
 
char hello[13] = "hello world!";
char hello2[13] = "hello hello!";



void servo_cb( const std_msgs::UInt16& cmd_msg){
  //servo.write(cmd_msg.data); //set servo angle, should be from 0-180  
  digitalWrite(13, HIGH-digitalRead(13));  //toggle led  
}


ros::Subscriber<std_msgs::UInt16> sub("servo", servo_cb);


void setup()
{
  pinMode(13, OUTPUT);
  //servo.attach(9); //attach it to pin 9
  nh.initNode();
  nh.advertise(chatter);
  nh.advertise(chatter2);
  nh.subscribe(sub);
}

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

參考
rosserial_python serial_node.py分析
https://www.cnblogs.com/Montauk/p/7158597.html

rosserial_python serial_node.py分析--補遺
https://www.cnblogs.com/Montauk/p/7161927.html
 

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章