** 一個(gè)節(jié)點(diǎn)的誕生**
在建立連接之前,首先要有節(jié)點(diǎn)。
節(jié)點(diǎn)就是一個(gè)獨(dú)立的程序,它運(yùn)行起來后就是一個(gè)普通的進(jìn)程,與計(jì)算機(jī)中其它的進(jìn)程并沒有太大區(qū)別。
一個(gè)問題是:ROS中為什么把一個(gè)獨(dú)立的程序稱為“節(jié)點(diǎn)”
這是因?yàn)镽OS沿用了計(jì)算機(jī)網(wǎng)絡(luò)中“節(jié)點(diǎn)”的概念。
在一個(gè)網(wǎng)絡(luò)中,例如互聯(lián)網(wǎng),每一個(gè)上網(wǎng)的計(jì)算機(jī)就是一個(gè)節(jié)點(diǎn)。前面我們看到的客戶端、服務(wù)器這樣的稱呼,也是從計(jì)算機(jī)網(wǎng)絡(luò)中借用的。
下面來看一下節(jié)點(diǎn)是如何誕生的。我們?cè)诘谝淮问褂肦OS時(shí),一般都會(huì)照著官方教程編寫一個(gè)talker和一個(gè)listener節(jié)點(diǎn),以熟悉ROS的使用方法。
我們以talker為例,它的部分代碼如下。
#include "ros/ros.h"
int main(int argc, char **argv)
{
/* You must call one of the versions of ros::init() before using any other part of the ROS system. */
ros::init(argc, argv, "talker");
ros::NodeHandle n;
main函數(shù)里首先調(diào)用了init()函數(shù)初始化一個(gè)節(jié)點(diǎn),該函數(shù)的定義在init.cpp文件中。
當(dāng)我們的程序運(yùn)行到init()函數(shù)時(shí),一個(gè)節(jié)點(diǎn)就呱呱墜地了。
而且在出生的同時(shí)我們還順道給他起好了名字,也就是"talker"。
名字是隨便起的,但是起名是必須的。
我們進(jìn)入init()函數(shù)里看看它做了什么,代碼如下,看上去還是挺復(fù)雜的。它初始化了一個(gè)叫g(shù)_global_queue的數(shù)據(jù),它的類型是CallbackQueuePtr。
這是個(gè)相當(dāng)重要的類,叫“回調(diào)隊(duì)列”,后面還會(huì)見到它。init()函數(shù)還調(diào)用了network、master、this_node、file_log、param這幾個(gè)命名空間里的init初始化函數(shù)各自實(shí)現(xiàn)一些變量的初始化,這些變量都以g開頭,例如g_host、g_uri,用來表明它們是全局變量。
其中,network::init完成節(jié)點(diǎn)主機(jī)名、IP地址等的初始化,master::init獲取master的URI、主機(jī)號(hào)和端口號(hào)。
this_node::init定義節(jié)點(diǎn)的命名空間和節(jié)點(diǎn)的名字,沒錯(cuò),把我們給節(jié)點(diǎn)起的名字就存儲(chǔ)在這里。file_log::init初始化日志文件的路徑。
void init(const M_string& remappings, const std::string& name, uint32_t options)
{
if (!g_atexit_registered) {
g_atexit_registered = true;
atexit(atexitCallback);
}
if (!g_global_queue) {
g_global_queue.reset(new CallbackQueue);
}
if (!g_initialized) {
g_init_options = options;
g_ok = true;
ROSCONSOLE_AUTOINIT;
// Disable SIGPIPE
#ifndef WIN32
signal(SIGPIPE, SIG_IGN);
#else
WSADATA wsaData;
WSAStartup(MAKEWORD(2, 0), &wsaData);
#endif
check_ipv6_environment();
network::init(remappings);
master::init(remappings);
// names:: namespace is initialized by this_node
this_node::init(name, remappings, options);
file_log::init(remappings);
param::init(remappings);
g_initialized = true;
}
}
完成初始化以后,就進(jìn)入下一步ros::NodeHandle n定義句柄。
我們?cè)龠M(jìn)入node_handle.cpp文件,發(fā)現(xiàn)構(gòu)造函數(shù)NodeHandle::NodeHandle調(diào)用了自己的construct函數(shù)。然后,順藤摸瓜找到construct函數(shù),它里面又調(diào)用了ros::start()函數(shù)。
沒錯(cuò),我們又繞回到了init.cpp文件。
ros::start()函數(shù)主要實(shí)例化了幾個(gè)重要的類,如下。
完成實(shí)例化后馬上又調(diào)用了各自的start()函數(shù),啟動(dòng)相應(yīng)的動(dòng)作。
這些都做完了以后就可以發(fā)布或訂閱消息了。
一個(gè)節(jié)點(diǎn)的故事暫時(shí)就到這了。
TopicManager::instance()- >start();
ServiceManager::instance()- >start();
ConnectionManager::instance()- >start();
PollManager::instance()- >start();
XMLRPCManager::instance()- >start();
-
計(jì)算機(jī)
+關(guān)注
關(guān)注
19文章
7425瀏覽量
87722 -
節(jié)點(diǎn)
+關(guān)注
關(guān)注
0文章
217瀏覽量
24386 -
網(wǎng)絡(luò)
+關(guān)注
關(guān)注
14文章
7519瀏覽量
88641 -
ROS
+關(guān)注
關(guān)注
1文章
276瀏覽量
16967
發(fā)布評(píng)論請(qǐng)先 登錄
相關(guān)推薦
評(píng)論