ROS的数据通信是以XML-RPC的方式,在graph结构中以topic,service和param的方式传输数据,天生的数据交互存在一定的延时和阻塞。Nodelet 包就是改善这一状况设计的, 使得多个算法运行在同一个过程中,并且算法间数据传输无需拷贝就可实现。 详见http://wiki.ros.org/nodelet。 简单的讲就是可以将以前启动的多个node捆绑在一起manager,使得同一个manager里面的topic的数据传输更快,数据通讯中roscpp采用boost shared pointer方式进行publish调用,实现zero copy。
1. 特点
1,1 nodelets间数据传输zero copy,有效避免数据copy和网络传输代价
1.2 支持pulgin的方式动态加载
1.3 使用C++ ROS的接口方式
2. nodelet 基类
2.1 定义基类nodelet::Nodelet, 任何nodelet继承自它可以使用plugin的方式动态加载。
2.2 提供命名空间,参数可remap
2.3 nodelet的manager的过程可以加载更多的nodelets. 同一个manager过程的nodelet数据传输zero copy .
3. 基本使用
参数的使用方式详见代码: https://github.com/ros/nodelet_core/blob/indigo-devel/nodelet/src/nodelet.cpp
参数解析 + nodelet::Loader / NodeletInterface
nodelet load pkg/Type manager - Launch a nodelet of type pkg/Type on manager manager //向manager中loader nodelet nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node //程序复用,相当启动一个普通node nodelet unload name manager - Unload a nodelet a nodelet by name from manager //从manager移除nodelet nodelet manager - Launch a nodelet manager node //创建mananger
4. 例程
(改自https://github.com/ros/common_tutorials/blob/hydro-devel/nodelet_tutorial_math/src/plus.cpp)
4.1 cmakeLists
cmake_minimum_required(VERSION 2.8.3)
project(nodelet_test_pkg)
find_package(catkin REQUIRED COMPONENTS nodelet roscpp std_msgs)#
## Setup include directories
include_directories(${catkin_INCLUDE_DIRS})
catkin_package(
)
add_library(nodelet_test_lib plus.cpp)
target_link_libraries(nodelet_test_lib ${catkin_LIBRARIES})
4.2 package
<package>
<name>nodelet_test_pkg</name>
<version>0.0.0</version>
<description>Nodelet test.</description>
<maintainer email="huasheng_zyh@163.com">kint zhao</maintainer>
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>nodelet</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>nodelet</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<export>
<nodelet plugin="${prefix}/nodelet_test_plugin.xml"/>
</export>
</package>
4.3 pulgin
<library path="lib/libnodelet_test_lib">
<class name="nodelet_ns/Plus" type="nodelet_ns::Plus" base_class_type="nodelet::Nodelet">
<description>
A node to add a value and republish.
</description>
</class>
</library>
注:Library path 是相对位置。 说明参考:
http://wiki.ros.org/pluginlib/PluginDescriptionFile
- pluginlib/
- Tutorials/
- Writing and Using a Simple Plugin
4.4 launch
<launch> <node pkg="nodelet" type="nodelet" name="manager_1" args="manager" output="screen"/> <node pkg="nodelet" type="nodelet" name="test1" args="load nodelet_ns/Plus manager_1" output="screen"/> <node pkg="nodelet" type="nodelet" name="test2" args="load nodelet_ns/Plus manager_1" output="screen"/> <node pkg="nodelet" type="nodelet" name="test3" args="load nodelet_ns/Plus manager_1" output="screen"/> <node pkg="nodelet" type="nodelet" name="manager_2" args="manager" output="screen"/> <node pkg="nodelet" type="nodelet" name="test4" args="load nodelet_ns/Plus manager_2" output="screen"/> <node pkg="nodelet" type="nodelet" name="test5" args="load nodelet_ns/Plus manager_2" output="screen"/> <node pkg="nodelet" type="nodelet" name="test6" args="standalone nodelet_ns/Plus " output="screen"/> </launch>
4.5 cpp
#include <pluginlib/class_list_macros.h> #include <nodelet/nodelet.h> #include <ros/ros.h> #include <std_msgs/Float64.h> #include <stdio.h> #include <math.h> //fabs namespace nodelet_ns { class Plus : public nodelet::Nodelet { public: Plus() : value_(0) {} private: virtual void onInit() { ros::NodeHandle& private_nh = getPrivateNodeHandle(); private_nh.getParam("value", value_); pub = private_nh.advertise<std_msgs::Float64>("out", 10); sub = private_nh.subscribe("in", 10, &Plus::callback, this); } void callback(const std_msgs::Float64::ConstPtr& input) { std_msgs::Float64Ptr output(new std_msgs::Float64()); output->data = input->data + value_; NODELET_DEBUG("Adding %f to get %f", value_, output->data); pub.publish(output); } ros::Publisher pub; ros::Subscriber sub; double value_; }; PLUGINLIB_DECLARE_CLASS(nodelet_ns, Plus, nodelet_ns::Plus, nodelet::Nodelet);//******* }
4.6 rqt_graph
从graph中你也应该可以直观的看出数据交互的方式。