【磕盐随记】Nodelet类的简明使用

前言

一直不太懂ROS的Nodelet,今天佳爷给我拿他的 Elastic-Tracker 作为例子给我讲了一下,在此简单记录,方便后续使用。

一、Nodelet的工作原理

nodelet是用来方便ros的节点之间通信的。因为ros不同的节点之间是不同的进程,进程与进程之间是没有办法通过指针共享变量的(同一进程的不同线程之间是可以的),那么如果我想在两个节点之间高频大数据量的传递一些信息,例如globalMap,那么普通的节点之间的话题通信就会有明显的延时和阻塞。

Nodelet自己就是一个节点,即一个进程,他将两个要通信的节点管理在自己的不同线程下,通过线程之间传递指针的方式,直接共享变量内存,从而实现消息的高效传递。换句话说,Nodelet可以将多个node捆绑在一起管理,使得同一个manager里面的topic的数据传输更快。

二、具体使用(以 Elastic-Tracker 为例)

现在我有两个节点(mapping和planning)要通信,想通过Nodelet来加速,步骤如下:

1、启动 nodelet manage

启动 nodelet manager节点,并分配一定数量的线程

  <node pkg="nodelet" type="nodelet" name="manager" args="manager" output="screen">
    <param name="num_worker_threads" value="16"/>
  </node>

2、在mapping节点中

首先,在package.xml中调用nodelet库(elastic-tracker中是写了个nodelet_plugin.xml然后在package.xml中写了个路径的prefix,两种方法应该都能用)

<library path="lib/libmapping_nodelet">
  <class name="mapping/Nodelet" type="mapping::Nodelet" base_class_type="nodelet::Nodelet">
    <description></description>
  </class>
</library>

然后,在mapping节点定义nodelet子类,并重写oninit方法,并将命名空间也定义为mapping,此外,还要在这个文件的最后加上PLUGINLIB(这个我不太懂,直接套模版吧)

namespace mapping {

// 这里可以写一些其他的东西
// 在这个nameSpace里面的话题通信就会自动被加速(前提是消息必须是Ptr哈)
// ...

class Nodelet : public nodelet::Nodelet
{
// 这里可以初始化一些自己的类和变量什么的,具体使用方式可以自己摸索
// ...

// 必须重写父类虚函数,至于这个oninit里面写什么,就看你自己了
// 需要注意的是,被nodelet manager管理的,是没有main函数的
// 所以如果你的这个node需要初始化,就需要自己写个init,然后放在oninit中
  void onInit(void) {
    ros::NodeHandle nh(getMTPrivateNodeHandle());
    initThread_ = std::thread(std::bind(&Nodelet::init, this, nh));
  }    
}
}

#include <pluginlib/class_list_macros.h>
PLUGINLIB_EXPORT_CLASS(mapping::Nodelet, nodelet::Nodelet);

最后在launch中使用nodelet 加载 mapping

  <node pkg="nodelet" type="nodelet" name="mapping" args="load mapping/Nodelet manager" output="screen">
    <!-- parameters -->
    <!-- 这个其实就代替了node来启动自己本身的节点,而是用load的方式将mapping加载到nodelet -->
  </node>

3、在planning节点中

处理方式与mapping处理方法一致,都是要放在nodelet中,重写oninit,然后使用load加载进nodelet

三、参考连接

Nodelet API:【链接】

Elastic-Tracker:【链接】

  • 1
    点赞
  • 5
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值