1、cpp文件中添加nodelet子类
注意nodehandle要用nodelet的getNodeHandle()所提供的。因为nodelet manager会给每个nodelet节点的nodehandle单独新建一个线程处理它的回调。
#include <ros/ros.h>
#include "sss_sim_env/TimeServer.hpp"
#include <nodelet/nodelet.h>
// 定义了一个SimClock类,继承了nodelet
class SimClock :public nodelet::Nodelet
{
public:
SimClock(){}
public:
void onInit()
{
ros::NodeHandle nh = getNodeHandle();
ros::NodeHandle nh_private = getPrivateNodeHandle();
// ros::NodeHandle nh = getMTNodeHandle();
// ros::NodeHandle nh_private = getMTPrivateNodeHandle();
time_server = std::make_unique<TimeServer>(nh, nh_private);
ROS_INFO("SimClock Inited");
// NODELET_DEBUG("My debug statement");
// NODELET_DEBUG_STREAM("my debug statement " << (double) 1.0)
// NODELET_DEBUG_COND( 1 == 1, "my debug_statement")
// NODELET_DEBUG_STREAM_COND( 1 == 1, "my debug statement " << (double) 1.0)
}
private:
std::unique_ptr<TimeServer> time_server;
};
#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(SimClock, nodelet::Nodelet);
可以对比一下,如果不用nodelet,正常的主程序cpp应该是这样:
#include <ros/ros.h>
#include "sss_sim_env/TimeServer.hpp"
int main(int argc, char **argv)
{
ros::init(argc, argv, "sim_clock");
ros::NodeHandle nh_private("~");
ros::NodeHandle nh;
//Use unique_ptr to auto-destory the object when exiting.
std::unique_ptr<TimeServer> time_server(new TimeServer(nh, nh_private));
ros::spin();
return 0;
}
2、添加plugins/nodelet_plugins.xml
在src同层文件夹添加plugins/nodelet_plugins.xml
<!--这里的path="",修改成path="lib/lib{包名}",
包名就是CMakeLists.txt里面定义的add_library(包名 )
我这里就是path="lib/libsim_clock"
-->
<library path="lib/libsim_clock" >
<!-- name: launch文件里面 load 后面接着的插件名
type: c++文件定义的类名
如 name="aaa/nodeletclass1",那么,launch文件对应启动如下:
<node pkg="nodelet" type="nodelet" name="nodeletclass1"
args="load aaa/nodeletclass1 nodelet_manager" output="screen">
-->
<class name="sss_sim_env/sim_clock_nodelet" type="SimClock" base_class_type="nodelet::Nodelet">
<description>
Simulation clock that determines the simulation time process.
</description>
</class>
</library>
3、修改CmakeLists.txt
find_package(catkin REQUIRED COMPONENTS
roscpp
nodelet #添加nodelet
)
# add_executable 改成 add_library
add_library(sim_clock # 包名,会生成libsim_clock.so
src/sim_clock/sim_clock.cpp
src/sim_clock/TimeServer.cpp)
# 根据实际情况选做
target_link_libraries(sim_clock
${catkin_LIBRARIES}
)
# 根据实际情况选做
add_dependencies(sim_clock
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS} )
4、修改package.xml
加入
<build_depend>nodelet</build_depend>
<exec_depend>nodelet</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
<nodelet plugin="${prefix}/plugins/nodelet_plugins.xml" />
</export>
5、编写launch文件
<?xml version="1.0"?>
<launch>
<node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen">
</node>
<node pkg="nodelet" type="nodelet" name="sim_clock_nodelet" args="load sss_sim_env/sim_clock_nodelet /nodelet_manager" output="screen">
</node>
</launch>
注意这里 load sss_sim_env/sim_clock_nodelet /nodelet_manager 时, nodelet_manager前面加了斜杠,表示的就是绝对名称,不受加<group ns="xxx">命名空间的影响。
nodelet也是可以用<group ns="xxx">来区分命名空间的,比如:
<?xml version="1.0"?>
<launch>
<arg name="use_nodelet_manager" value="true"/>
<group ns="$(arg namespace)">
<group if="$(arg use_nodelet_manager)"> <!-- /nodelet_manager should be lauched by sim_clock.launch -->
<node pkg="nodelet" type="nodelet" name="sim_clock_nodelet" args="load sss_sim_env/sim_clock_nodelet /nodelet_manager" output="screen">
</node>
</group>
<group unless="$(arg use_nodelet_manager)"> <!--launched as a normal ROS node -->
<node pkg="nodelet" type="nodelet" name="sim_clock_nodelet" args="standalone sss_sim_env/sim_clock_nodelet" output="screen">
</node>
</group>
</group>
</launch>
这里如果用standalone而不是load来加载nodelet插件,那么和单独启动一个ROS节点进程没有区别。
顺便提一下,nodelet能够实现这种动态加载,是基于ROS的pluginlib动态加载功能,将原先本应该是单独进程的程序变成一个个class库,然后动态加载到一个进程中。
nodelet的好处:进程内的ROS话题发布和接收可以省去序列化和反序列化、socket通信的过程,而是通过shared_ptr共享内存实现,对于数据量大的话题也许可以降低延迟减少丢包。但前提是publisher必须用shared_ptr的方法发布话题,比如:
ros::Publisher pub = nh.advertise<std_msgs::String>("topic_name", 5);
std_msgs::StringPtr str_msg(new std_msgs::String);
str_msg->data = "hello world";
pub.publish(str);
// 注意由于str_msg是一个shared_ptr指针,在这个局部作用域内(大括号内)str_msg不应该再被修改,否则发布的消息也会改变
Nodelet不支持python。