侧边栏壁纸
  • 累计撰写 131 篇文章
  • 累计创建 16 个标签
  • 累计收到 4 条评论

目 录CONTENT

文章目录
ROS   

ROS Nodelet

ROS Nodelet 包提供一种在单个机器上、在单个进程中运行多个算法的方法,并在算法之间实现零拷贝传输。在一个 node 里面,利用直接指针传递可以实现在 publishsubscribe 调用时的零拷贝。在图片、点云的场景中尤其常用。

nodelets 允许将多个类动态加载同一个 node 里,同时还提供独立命名空间,从而使得这些 nodelets 尽管运行在同一个进程里,但却仍然像单独的 node 一样工作。也就实现了在单进程(node)里运行**多个 nodelet **的效果。

Nodelet 的例子 Plus

首先,将我们需要的功能包装为,类需要继承 nodelet::Nodelet ,并覆盖重写成员 onInit() ,最后 PLUGINLIB_DECLARE_CLASS 提示插件的存在

namespace nodelet_tutorial_math		// 声明命名空间
{
class Plus : public nodelet::Nodelet	// 声明类 Plus,公共继承 nodelet 
{
public:
  Plus(): value_(0)		// 构造函数,并初始化定义value_为0
  {}

private:
  // 
  // 当nodelet插件类被nodelet_manager加载时,nodelet插件类的onInit方法就会被调用,用于初始化插件类
  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_EXPORT_CLASS告知编译器Plus是一个插件
PLUGINLIB_DECLARE_CLASS(nodelet_tutorial_math, Plus, nodelet_tutorial_math::Plus, nodelet::Nodelet);
}

在终端中调用

首先要启动 Nodelet 管理器,用于监听 ROS 的服务请求,并动态加载 nodelet 模块。

roscore
rosrun nodelet nodelet manager __name:=nodelet_manager

然后通过 nodelet 的 load 指令动态加载模块,命令的含义为:
向创建的 nodelet_manager 中加载 pkg/Type 为 nodelet_tutorial_math/Plus 的 nodelet节 点,并将其重命名为 nodelet1,nodelet1/in 话题重映射为 foo,value 值设为 1.1

rosrun nodelet nodelet load nodelet_tutorial_math/Plus nodelet_manager __name:=nodelet1 nodelet1/in:=foo _value:=1.1

通过 rosnode listrostopic list 指令查看当前正在运行的节点主题

利用 rqt_graph 指令,可以更直观地查看节点间的交互方式

rqt_graph

image-1655826510992

我们也可以自主发布一个/foo主题的消息,并监测/nodelet1/out的输出。

rostopic pub /foo std_msgs/Float64 5.0 -r 10
rostopic echo /nodelet1/out

launch 文件加载

通过 launch 文件可以更加轻松的加载多个 nodelet 并管理配置。

<launch>
    <!-- 首先启动 manager 节点,创建一个名为 standalone_nodelet 的manager  -->
    <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen"/>

  	<!-- 加载一个 Nodelet,其中属性args描述了加载环境配置,目标Nodelet就是Plus,并将之与standalone_nodelet绑定。
		   并使用 remap 标签将 Plus 的输出重映射到 Plus2 的输入  -->
    <node pkg="nodelet" type="nodelet" name="Plus" args="load nodelet_tutorial_math/Plus standalone_nodelet" output="screen">
        <remap from="/Plus/out" to="Plus2/in"/>
    </node>          
	
  	<!-- 再加载一个Nodelet,命名为Plus2,其arg与之前一样。
		  并使用 rosparam 子标签,加载运行参数,在文件 plus_default.yaml 中将参数value取值为10 -->
    <node pkg="nodelet" type="nodelet" name="Plus2" args="load nodelet_tutorial_math/Plus standalone_nodelet" output="screen">
        <rosparam file="$(find nodelet_tutorial_math)/plus_default.yaml"/>
    </node>

  	<!-- 接着用 standalone 的形式再加载命名为 Plus3,这个方式加载的看不到显式的 Nodelet 与管理器之间的绑定关系,很少用到。 
		  在其子标签param中定义了Plus3的运行时 value 为2.5。子标签 remap 中将 Plus2 发布的 out 主题重映射到了 Plus3 的 in 主题上 -->
    <node pkg="nodelet" type="nodelet" name="Plus3" args="standalone nodelet_tutorial_math/Plus" output="screen">
        <param name="value" type="double" value="2.5"/>
        <remap from="Plus3/in" to="Plus2/out"/>
    </node>
</launch>

运行该 launch 文件,并订阅输出:

roslaunch nodelet_tutorial_math plus.launch
rostopic pub /Plus2 std_msgs/Float64 1.0 -r 10
rostopic echo /Plus2/out
rostopic echo /Plus3/out

使用 rqt_graph 命令查看节点,可以发现用 standalone 加载的 Plus3 的绑定关系并不一样。

完整代码结构

TypeError: Cannot read properties of undefined (reading 'v')

.h 头文件(也可以没有)

声明,公共继承 nodelet ,并重写 onInit() 虚函数。所有的初始化工作都应该在这个函数中完成。

#include <nodelet/nodelet.h>

namespace example_pkg
{
    class ExNodeletClass : public nodelet::Nodelet
    {
        public:
            virtual void onInit();
    };
}

.cpp 源文件

为了允许动态加载,它必须被标记为导出类。这通过特殊宏PLUGINLIB_EXPORT_CLASS / PLUGINLIB_DECLARE_CLASS来完成。

#include <pluginlib/class_list_macros.h>

namespace example_pkg
{
    void ExNodeletClass::onInit()
    {
        NODELET_DEBUG("Initializing nodelet...");
    }
}

PLUGINLIB_EXPORT_CLASS(example_pkg::ExNodeletClass, nodelet::Nodelet)

nodelet_plugins 插件描述文件

插件描述文件是一个 XML 文件,用于存储有关插件的所有重要信息。它包含有关插件所在的库信息插件名称插件类型等。一般该文件应与 package.xml 放置在同一路径下。

<library path="lib/libExNodeletClass">
  <class name="example_pkg/ExNodeletClass" type="example_pkg::ExNodeletClass" base_class_type="nodelet::Nodelet">
  <description>
  This is my nodelet.
  </description>
  </class>
</library>

package.xml 依赖

添加声明,表示包中有一个 nodelet 依赖插件

<build_depend>nodelet</build_depend>
<run_depend>nodelet</run_depend>
<export>
  <nodelet plugin="${prefix}/nodelet_plugins.xml" />
</export>

CMakeLists.txt 编译文件

add_library(nodelet_test src/test.cpp)  # 描述编译对象
target_link_libraries(nodelet_test ${catkin_LIBRARIES})  # 描述链接关系
add_dependencies(nodelet_test ${catkin_EXPORTED_LIBRARIES}) 	# 描述依赖关系

# 编译安装可执行文件
install(TARGETS 
   nodelet_test
   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

# 安装插件 xml 文件
install(FILES
   nodelet_plugins.xml
   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

.launch 调用

启动 nodelet manager,加载 nodelet 到 manager 中。

<launch>
  <node pkg="nodelet" type="nodelet" name="standalone_nodelet"  args="manager" output="screen"/>

  <node pkg="nodelet" type="nodelet" name="MyNodeletClass" 
        args="load example_pkg/ExNodeletClass standalone_nodelet" output="screen">
  </node>
</launch>
0

评论区