基本使用方法:
nodelet usage: nodelet load pkg/Type manager - Launch a nodelet of type pkg/Type on manager manager nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node nodelet unload name manager - Unload a nodelet a nodelet by name from manager nodelet manager - Launch a nodelet manager node
1.定义基类nodelet::Nodelet,用来动态加载。所有的nodelet都会继承这个基类,使用pluginlib动态加载。
2.提供namespace命名空间,自动remapping arguments 和 parameters,看起来他们是a first class 节点。
3.会有一个nodelet_manager process,一个或者更多的nodelets可以加载进去。他们之间的任何数据交换都可用boost shared 指针做到zero copy roscpp 发布。
nodelet基类:nodelet::Nodelet
public:
1 Nodelet() //当动态加载的时候默认的构造函数 2 // nodelet starts。参数是manager用来开启nodelet的。这个会初始化nodelet基类,然后调用子类的onInit()函数。
void init (const std::string& name, const ros::M_string& remapping_args, const std::vector<std::string>& my_argv);
protected:
1 std::string getName() //获得nodelet的名字 2 ros::NodeHandle& getNodeHandle () // 获得node handle (provides this nodelets custom remappings and name) 3 ros::NodeHandle& getPrivateNodeHandle () // 获得private node handle (provides this nodelets custom remappings in its private namespace) 4 ros::NodeHandle& getMTNodeHandle () // Get the node handle with 多线程回调队列. (provides this nodelets custom remappings and name) 5 ros::NodeHandle& getMTPrivateNodeHandle () // Get the private node handle with 多线程回调队列. (provides this nodelets custom remappings in its private namespace) 6 ros::CallbackQueue& getMTCallbackQueue () // 获取回调队列 (threadpool available from the manager) 7 std::vector<std::string> getMyArgv() //to the nodelet stripped of ROS and nodelet specific args.
在子类中用于启动ROS API的初始化方法:
1 virtual void onInit () = 0 //纯虚函数,需要被子类重写。所有的ROS 基础设施的初始化都要放到这个函数里
nodelet宏命令:
They operate by setting up a named logger in the name of the nodelet running so that you can differentiate between the output of two of the same type nodelets running on the same manager. They also have the advantage that you can turn one specific nodelet into debug, instead of all nodelets of a specific type.
1 #include "nodelet/nodelet.h" 2 3 //... inside a nodelet method 4 NODELET_DEBUG("My debug statement") 5 NODELET_DEBUG_STREAM("my debug statement " << (double) 1.0) 6 NODELET_DEBUG_COND( 1 == 1, "my debug_statement") 7 NODELET_DEBUG_STREAM_COND( 1 == 1, "my debug statement " << (double) 1.0)
在nodelet中publish:
要想zero copy,必须要以shared_ptrs形式发布消息.
线程模型:
nodelet manager有线程池,由这个manager内所有nodelets共享.由 "num_worker_threads"参数设置.
在nodelet中有两个可能的线程API运行。默认的线程模型只有单线程for 所有的回调。也有多线程API。
onInit:在初始化时调用,不应该block,或者做重要的事情
单线程API:使用getNodeHandle()和getPrivateNodeHandle()方法保证所有的回调arrive serially.(串行)
多线程 API:使用getMTNodeHandle()和getMTPrivateNodeHandle()方法,回调会分布到manager的线程池中
Additional Threads:nodelet用来创建自己的线程,这些线程在合适的时候析构掉。
线程共享:所有的nodelets共享manager的线程池。如果nodelets在blocking 线程,他们会组阻止其他的nodelets get callback。要确保manager配置好了足够的线程来阻止blocking。注意:即使是单线程Node Handles也会消耗掉线程池的一个线程/per nodelet。
Running a nodelet:
1首先安装一个例子:
rosmake nodelet_tutorial_math
roscore
2然后启动一个manager:
nodelet需要在a NodeletManager中运行。nodelet manager是C++程序,用来监听ROS服务,will be the executable in which the nodelet is dynamically loaded.这里我们运行的是a standalone manager,但是在很多例子中这些managers will be embedded within running nodes.(manager内含在运行的节点中?)
rosrun nodelet nodelet manager __name:=nodelet_manager
这里把manager重命名为nodelet_manager
3.启动nodelet
远程启动nodelet by using the nodelet executable as well.
What this code does: The nodelet executable, called here, will 与 nodelet_manager 通讯and ask it to 实例化 一个 the nodelet_tutorial_math/Plus nodelet的实例 . 然后他会传递name, nodelet1, and also any remappings if applied to the code inside the nodelet. And parameters appear in the right namespace too.
rosrun nodelet nodelet load nodelet_tutorial_math/Plus nodelet_manager __name:=nodelet1 nodelet1/in:=foo _value:=1.1
查看rostopic list:
/foo /nodelet1/out
查看rosnode list:
/nodelet1
/nodelet_manager
4.测试
rostopic pub /foo std_msgs/Float64 5.0 -r 10 rostopic echo /nodelet1/out
会显示
6.1 which is 5.0 + 1.1
这里有一个launch文件的例子 (available in nodelet_tutorial_math pkg) ,多个nodelets运行在同一个standalone manager:
<launch> <node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager"/> <node pkg="nodelet" type="nodelet" name="Plus" args="load nodelet_tutorial_math/Plus standalone_nodelet"> <remap from="/Plus/out" to="remapped_output"/> </node> <rosparam param="Plus2" file="$(find nodelet_tutorial_math)/plus_default.yaml"/> <node pkg="nodelet" type="nodelet" name="Plus2" args="load nodelet_tutorial_math/Plus standalone_nodelet"> <rosparam file="$(find nodelet_tutorial_math)/plus_default.yaml"/> </node> <node pkg="nodelet" type="nodelet" name="Plus3" args="standalone nodelet_tutorial_math/Plus"> <param name="value" type="double" value="2.5"/> <remap from="Plus3/in" to="Plus2/out"/> </node> </launch>
Porting nodes to nodelets
- 增加必要的#includes
- g去掉 int main()
- 子类 nodelet::Nodelet
- 把constructor的代码移到onInit()
- 添加PLUGINLIB_EXPORT_CLASS 宏命令
-
添加 <build_depend> 和 <run_depend> dependencies on nodelet in the package manifest.
-
在package manifest的<export>部分 添加 <nodelet>项
- 建立 .xml文件,将nodelet定义为一个 plugin /插件
- make the necessary changes to CMakeLists.txt (comment out a rosbuild_add_executable, add a rosbuild_add_library)
Minimal Nodelet:
1.MyNodeletClass.h
1 #include <nodelet/nodelet.h> 2 3 namespace example_pkg 4 { 5 6 class MyNodeletClass : public nodelet::Nodelet 7 { 8 public: 9 virtual void onInit(); 10 }; 11 12 }
2.MyNodeletClass.cpp
1 // this should really be in the implementation (.cpp file) 2 #include <pluginlib/class_list_macros.h> 3 4 // watch the capitalization carefully 5 PLUGINLIB_EXPORT_CLASS(example_pkg::MyNodeletClass, nodelet::Nodelet) 6 7 namespace example_pkg 8 { 9 void MyNodeletClass::onInit() 10 { 11 NODELET_DEBUG("Initializing nodelet..."); 12 } 13 }
3.nodelet_plugins.xml
<library path="lib/libMyNodeletClass"> <class name="example_pkg/MyNodeletClass" type="example_pkg::MyNodeletClass" base_class_type="nodelet::Nodelet"> <description> This is my nodelet. </description> </class> </library>
4.package.xml
... <build_depend>nodelet</build_depend> <run_depend>nodelet</run_depend> <export> <nodelet plugin="${prefix}/nodelet_plugins.xml" /> </export> ...
5.mynodelet.launch
<launch> <node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/> <node pkg="nodelet" type="nodelet" name="MyNodeletClass" args="load example_pkg/MyNodeletClass standalone_nodelet" output="screen"> </node> </launch>
浙公网安备 33010602011771号