//init.h 文 件
#ifndef ROSCPP_INIT_H
#define ROSCPP_INIT_H
#include "ros/forwards.h"
#include "ros/spinner.h"
#include "common.h"
namespace ros{
namespace init_options{
enum InitOption{
NoSigintHandler = 1 << 0,
AnonymousName = 1 << 1,
NoRosout = 1 << 2,
}; //enum InitOption
}// namespace init_options
typedef init_options::InitOption InitOption;
//ROS的初始化功能,在使用句柄之前必须要调用初始化函数
ROSCPP_DECL void init(int &argc, char **argv, const std::string& name, uint32_t options = 0);
ROSCPP_DECL void init(const M_string& remappings, const std::string& name, uint32_t options = 0);
ROSCPP_DECL void init(const VP_string& remapping_args, const std::string& name, uint32_t options = 0);
//检查init()函数是否被调用
ROSCPP_DECL bool isInitialized();
//检查shutdown()函数是否被调用
ROSCPP_DECL bool isShuttingDown();
//进入事件循环,每次循环均调用回调函数
ROSCPP_DECL void spin();
ROSCPP_DECL void spin(Spinner& spinner);
//事件循环一次,只调用一次回调函数
ROSCPP_DECL void spinOnce();
//等待用户 Ctrl+C 终止程序
ROSCPP_DECL void waitForShutdown();
//检测是否需要退出程序
ROSCPP_DECL bool ok();
ROSCPP_DECL void shutdown();
//节点从ROS线程中关闭的请求
ROSCPP_DECL void requestShutdown();
ROSCPP_DECL void start();
ROSCPP_DECL bool isStarted();
ROSCPP_DECL CallbackQueue* getGlobalCallbackQueue();
//搜索给定的arg参数的命令行参数。如果此参数未找到,则返回空字符串
ROSCPP_DECL std::string getROSArg(int argc, const char* const* argv, const std::string& arg);
ROSCPP_DECL void removeROSArgs(int argc, const char* const* argv, V_string& args_out);
}//namespace ros
#endif
//init.cpp 文件 中的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);
#endif
//初始化network、master、this_node,file_log,分别在network.cpp,master.cpp,this_node.cpp...中有定义
//下面几个初始化函数将在下节介绍
network::init(remappings);
master::init(remappings);
this_node::init(name, remappings, options); // name参数指的就是当前节点
file_log::init(remappings);
param::init(remappings);
//初始化完成以后 全局初始化标记赋值为true
g_initialized = true;
}
}
//初始化函数,调用方式: ros::init(argc, argv, "node_name");
//还记得这条命令吗:rosrun turtlesim turtlesim_node __name:=my_turtle
//此时 argc = 4, argv = {“rosrun”,"turtlesim", "turtlesim_node", "__name:=my_turtle"}
void init(int& argc, char** argv, const std::string& name, uint32_t options){
//数据类型M_string的定义为:typedef std::map<std::string, std::string> M_string
M_string remappings;
int full_argc = argc;
// now, move the remapping argv's to the end, and decrement argc as needed
for (int i = 0; i < argc; ){
std::string arg = argv[i];
size_t pos = arg.find(":="); //找到参数“__name:=my_turtle”中的 :=
if (pos != std::string::npos){
std::string local_name = arg.substr(0, pos);
std::string external_name = arg.substr(pos + 2);
ROSCPP_LOG_DEBUG("remap: %s => %s", local_name.c_str(), external_name.c_str());
//local_name = "rosrun turtlesim turtlesim_node __name", external_name = "my_turtle"
remappings[local_name] = external_name;
// 参数“__name:=myturtle”移到命令的最后
char *tmp = argv[i];
for (int j = i; j < full_argc - 1; j++)
argv[j] = argv[j+1];
argv[argc-1] = tmp;
argc--; //参数数量减1
}
else{
i++; // move on, since we didn't shuffle anybody here to replace it
}
}
//此时的remappings 为 {"rosrun turtlesim turtlesim_node __name":"my_turtle"}
//调用上面的 void init(const M_string& remappings, const std::string& name, uint32_t options) 函数
init(remappings, name, options);
}
更多special reserved keywords 可参考:http://wiki.ros.org/action/fullsearch/Remapping%20Arguments?action=fullsearch&context=180&value=linkto%3A%22Remapping+Arguments%22