節點間通過XMLRPC建立連接
在一個節點剛啟動的時候,它并不知道其它節點的存在,更不知道它們在交談什么,當然也就談不上通信。
所以,它要先與master對話查詢其它節點的狀態,然后再與其它節點通信。
而節點與master對話使用的就是XMLRPC。
從這一點來看,master叫節點管理器確實名副其實,它是一個大管家,給剛出生的節點提供服務。
下面我們以兩個節點:talker和listener為例,介紹其通過XMLRPC建立通信連接的過程,如下圖所示。
- talker注冊
假設我們先啟動talker。啟動后,它通過1234端口使用XMLRPC向master注冊自己的信息,包含所發布消息的話題名。master會將talker的注冊信息加入注冊列表中;
2.listener注冊
listener啟動后,同樣通過XMLRPC向master注冊自己的信息,包含需要訂閱的話題名;
3.master進行匹配
master根據listener的訂閱信息從注冊列表中查找,如果沒有找到匹配的發布者,則等待發布者的加入,如果找到匹配的發布者信息,則通過XMLRPC向listener發送talker的地址信息。
4.listener發送連接請求
listener接收到master發回的talker地址信息,嘗試通過XMLRPC向talker發送連接請求,傳輸訂閱的話題名、消息類型以及通信協議(TCP或者UDP);
5.talker確認連接請求
talker接收到listener發送的連接請求后,繼續通過XMLRPC向listener確認連接信息,其中包含自身的TCP地址信息;
6.listener嘗試與talker建立連接
listener接收到確認信息后,使用TCP嘗試與talker建立網絡連接。
7.talker向listener發布消息
成功建立連接后,talker開始向listener發送話題消息數據,master不再參與。
從上面的分析中可以發現,前五個步驟使用的通信協議都是XMLRPC,最后發布數據的過程才使用到TCP。
master只在節點建立連接的過程中起作用,但是并不參與節點之間最終的數據傳輸。
節點在請求建立連接時會通過master.cpp文件中的execute()函數調用XMLRPC庫中的函數。
我們舉個例子,加入talker節點要發布消息,它會調用topic_manager.cpp中的TopicManager::advertise()函數,在函數中會調用execute()函數,該部分代碼如下。
XmlRpcValue args, result, payload;
args[0] = this_node::getName();
args[1] = ops.topic;
args[2] = ops.datatype;
args[3] = xmlrpc_manager_- >getServerURI();
master::execute("registerPublisher", args, result, payload, true);
其中,registerPublisher就是一個遠程過程調用的方法(或者叫函數)。節點通過這個遠程過程調用向master注冊,表示自己要發布發消息了。
你可能會問,registerPublisher方法在哪里被執行了呢?我們來到ros_comm-noetic-develtoolsrosmastersrcrosmaster路徑下,打開master_api.py文件,然后搜索registerPublisher這個方法,就會找到對應的代碼,如下。
匆匆掃一眼就知道,它在通知所有訂閱這個消息的節點,讓它們做好接收消息的準備。
你可能注意到了,這個被調用的XMLRPC是用python語言實現的。
也就是說,XMLRPC通信時只要報文的格式是一致的,不管C++還是python語言,都可以實現遠程調用的功能。
def registerPublisher(self, caller_id, topic, topic_type, caller_api):
try:
self.ps_lock.acquire()
self.reg_manager.register_publisher(topic, caller_id, caller_api)
# don't let '*' type squash valid typing
if topic_type != rosgraph.names.ANYTYPE or not topic in self.topics_types:
self.topics_types[topic] = topic_type
pub_uris = self.publishers.get_apis(topic)
sub_uris = self.subscribers.get_apis(topic)
self._notify_topic_subscribers(topic, pub_uris, sub_uris)
mloginfo("+PUB [%s] %s %s",topic, caller_id, caller_api)
sub_uris = self.subscribers.get_apis(topic)
finally:
self.ps_lock.release()
return 1, "Registered [%s] as publisher of [%s]"%(caller_id, topic), s
-
節點
+關注
關注
0文章
220瀏覽量
24456 -
管理器
+關注
關注
0文章
246瀏覽量
18549 -
MASTER
+關注
關注
0文章
104瀏覽量
11298 -
ROS
+關注
關注
1文章
278瀏覽量
17035
發布評論請先 登錄
相關推薦
評論