目录
- 一、前言
- 二、概念
- 三、作用
- 四、使用演示
- 4.1案例简介
- 4.2nodelet 基本使用语法
- 4.3内置案例调用
- 五、nodelet实现
- 5.1需求
- 5.2流程
- 5.3准备
- 5.4创建插件类并注册插件
- 5.5构建插件库
- 5.6使插件可用于ROS工具链
- 5.6.1配置xml
- 5.6.2导出插件
- 5.7执行
一、前言
ROS通信是基于Node(节点)的,Node使用方便、易于扩展,可以满足ROS中大多数应用场景,但是也存在一些局限性,由于一个Node启动之后独占一根进程,不同Node之间数据交互其实是不同进程之间的数据交互,当传输类似于图片、点云的大容量数据时,会出现延时与阻塞的情况,比如:
现在需要编写一个相机驱动,在该驱动中有两个节点实现:其中节点A负责发布原始图像数据,节点B订阅原始图像数据并在图像上标注人脸。如果节点A与节点B仍按照之前实现,两个节点分别对应不同的进程,在两个进程之间传递容量可观图像数据,可能就会出现延时的情况,那么该如何优化呢?
ROS中给出的解决方案是:Nodelet,通过Nodelet可以将多个节点集成进一个进程。
二、概念
nodelet软件包旨在提供在同一进程中运行多个算法(节点)的方式,不同算法之间通过传递指向数据的指针来代替了数据本身的传输(类似于编程传值与传址的区别),从而实现零成本的数据拷贝。
nodelet功能包的核心实现也是插件,是对插件的进一步封装:
不同算法被封装进插件类,可以像单独的节点一样运行;
在该功能包中提供插件类实现的基类:Nodelet;
并且提供了加载插件类的类加载器:NodeletLoader。
三、作用
应用于大容量数据传输的场景,提高节点间的数据交互效率,避免延时与阻塞。
四、使用演示
在ROS中内置了nodelet案例,先以该案例演示nodelet的基本使用语法。
4.1案例简介
以“ros- [ROS_DISTRO] -desktop-full”命令安装ROS时,nodelet默认被安装,如未安装,请调用如下命令自行安装:
sudo apt install ros-<<ROS_DISTRO>>-nodelet-tutorial-math
在该案例中,定义了一个Nodelet插件类:Plus,这个节点可以订阅一个数字,并将订阅到的数字与参数服务器中的 value 参数相加后再发布。
需求:再同一线程中启动两个Plus节点A与B,向A发布一个数字,然后经A处理后,再发布并作为B的输入,最后打印B的输出。
4.2nodelet 基本使用语法
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
4.3内置案例调用
1.启动roscore
2.启动manager
rosrun nodelet nodelet manager __name:=mymanager
注:__name:= 用于设置管理器名称。
3.添加nodelet节点
添加第一个节点:
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n1 _value:=100
添加第二个节点:
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n2 _value:=-50 /n2/in:=/n1/out
解释:
rosrun nodelet nodelet load nodelet_tutorial_math/Plus mymanager __name:=n1 _value:=100rosnode list 查看,nodelet 的节点名称是: /n1;
rostopic list 查看,订阅的话题是: /n1/in,发布的话题是: /n1/out;
rosparam list查看,参数名称是: /n1/value。
rosrun nodelet nodelet standalone nodelet_tutorial_math/Plus mymanager __name:=n2 _value:=-50 /n2/in:=/n1/out第二个nodelet 与第一个同理;
第二个nodelet 订阅的话题由 /n2/in 重映射为 /n1/out。
优化:也可以将上述实现集成进launch文件:
<launch><!-- 设置nodelet管理器 --><node pkg="nodelet" type="nodelet" name="mymanager" args="manager" output="screen" /><!-- 启动节点1,名称为 n1, 参数 /n1/value 为100 --><node pkg="nodelet" type="nodelet" name="n1" args="load nodelet_tutorial_math/Plus mymanager" output="screen" ><param name="value" value="100" /></node><!-- 启动节点2,名称为 n2, 参数 /n2/value 为-50 --><node pkg="nodelet" type="nodelet" name="n2" args="load nodelet_tutorial_math/Plus mymanager" output="screen" ><param name="value" value="-50" /><remap from="/n2/in" to="/n1/out" /></node></launch>
4.执行
向节点n1发布消息:
rostopic pub -r 10 /n1/in std_msgs/Float64 "data: 50.0"
打印节点n2发布的消息:
rostopic echo /n2/out
最终输出结果应该是:100。
五、nodelet实现
nodelet本质也是插件,实现流程与插件实现流程类似,并且更为简单,不需要自定义接口,也不需要使用类加载器加载插件类。
5.1需求
参考 nodelet 案例,编写 nodelet 插件类,可以订阅输入数据,设置参数,发布订阅数据与参数相加的结果。
5.2流程
1.准备;
2.创建插件类并注册插件;
3.构建插件库;
4.使插件可用于ROS工具链;
5.执行。
5.3准备
新建功能包,导入依赖: roscpp、nodelet;
5.4创建插件类并注册插件
#include "nodelet/nodelet.h"
#include "pluginlib/class_list_macros.h"
#include "ros/ros.h"
#include "std_msgs/Float64.h"namespace nodelet_demo_ns {
class MyPlus: public nodelet::Nodelet {public:MyPlus(){value = 0.0;}void onInit(){//获取 NodeHandleros::NodeHandle& nh = getPrivateNodeHandle();//从参数服务器获取参数nh.getParam("value",value);//创建发布与订阅对象pub = nh.advertise<std_msgs::Float64>("out",100);sub = nh.subscribe<std_msgs::Float64>("in",100,&MyPlus::doCb,this);}//回调函数void doCb(const std_msgs::Float64::ConstPtr& p){double num = p->data;//数据处理double result = num + value;std_msgs::Float64 r;r.data = result;//发布pub.publish(r);}private:ros::Publisher pub;ros::Subscriber sub;double value;};
}
PLUGINLIB_EXPORT_CLASS(nodelet_demo_ns::MyPlus,nodelet::Nodelet)
5.5构建插件库
CMakeLists.txt配置如下:
...
add_library(mynodeletlibsrc/myplus.cpp
)
...
target_link_libraries(mynodeletlib${catkin_LIBRARIES}
)
编译后,会在 工作空间/devel/lib/先生成文件: libmynodeletlib.so。
5.6使插件可用于ROS工具链
5.6.1配置xml
新建 xml 文件,名称自定义(比如:my_plus.xml),内容如下:
<library path="lib/libmynodeletlib"><class name="demo04_nodelet/MyPlus" type="nodelet_demo_ns::MyPlus" base_class_type="nodelet::Nodelet" ><description>hello</description></class>
</library>
5.6.2导出插件
<export><!-- Other tools can request additional information be placed here --><nodelet plugin="${prefix}/my_plus.xml" />
</export>
5.7执行
可以通过launch文件执行nodelet,示例内容如下:
<launch><node pkg="nodelet" type="nodelet" name="my" args="manager" output="screen" /><node pkg="nodelet" type="nodelet" name="p1" args="load demo04_nodelet/MyPlus my" output="screen"><param name="value" value="100" /><remap from="/p1/out" to="con" /></node><node pkg="nodelet" type="nodelet" name="p2" args="load demo04_nodelet/MyPlus my" output="screen"><param name="value" value="-50" /><remap from="/p2/in" to="con" /></node></launch>
运行launch文件,可以参考上一节方式向 p1发布数据,并订阅p2输出的数据。
参考视屏:赵虚左ros入门