10.3.2 nodelet 实现
优质
小牛编辑
137浏览
2023-12-01
10.3.2 nodelet实现
nodelet本质也是插件,实现流程与插件实现流程类似,并且更为简单,不需要自定义接口,也不需要使用类加载器加载插件类。
需求:参考 nodelet 案例,编写 nodelet 插件类,可以订阅输入数据,设置参数,发布订阅数据与参数相加的结果。
流程:
准备;
创建插件类并注册插件;
构建插件库;
使插件可用于ROS工具链;
执行。
1.准备
新建功能包,导入依赖: roscpp、nodelet;
2.创建插件类并注册插件
#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(){
//获取 NodeHandle
ros::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)
3.构建插件库
CMakeLists.txt配置如下:
...
add_library(mynodeletlib
src/myplus.cpp
)
...
target_link_libraries(mynodeletlib
${catkin_LIBRARIES}
)
编译后,会在 工作空间/devel/lib/
先生成文件: libmynodeletlib.so。
4.使插件可用于ROS工具链
4.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>
4.2导出插件
<export>
<!-- Other tools can request additional information be placed here -->
<nodelet plugin="${prefix}/my_plus.xml" />
</export>
5.执行
可以通过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输出的数据,最终运行结果也与上一节类似。