首页 关于
树枝想去撕裂天空 / 却只戳了几个微小的窟窿 / 它透出天外的光亮 / 人们把它叫做月亮和星星
目录

Nodelet

我们知道ROS中主要通过订阅者模式和服务器模式完成进程之间的通信工作,由于各个进程都有自己独立的内存空间,所以在传输图像等数据量较大的消息的时候,不可避免需要做很多数据拷贝的工作, 严重影响了系统的运行效率。

Nodelet就是为了解决这一问题而设计的,它可以让多个算法运行在一个进程中,也就是一个节点中。 roscpp对于运行在同一个节点中的消息发布订阅机制有优化,可以直接传递指针,降低了拷贝内存的操作。 为了利用这一特点,我们需要以插件的形式实现算法,由Nodelet来动态的加载这些插件,达到让各个模块都运行在一个节点中的目的。

1. 初识Nodelet

既然要让各个模块以插件的形式运行,那么就应当有一个插件的植入对象了。这个对象就是Nodelet管理器,它是一个C++程序用于监听ROS的服务请求,并动态加载nodelet模块。 我们可以用如下指令专门运行一个standalone形式的管理器,其实很多时候我们会将管理器嵌入到一个节点中。

    $ rosrun nodelet nodelet manager __name:=nodelet_manager

然后通过nodelet的load指令可以动态的加载模块,比如说官方教程中的Plus:

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

上述指令的最后把plus的订阅主题nodelet1/in重映射为foo,_value则是一个系统运行参数。我们可以通过rosnode list和rostopic list查看当前正在运行的节点和主题。 其中nodelet1和nodelet_manager就是我们刚刚运行的nodelet和管理器。消息/foo是重定向后的nodelet1/in主题,/nodelet1/out是nodelet1的输出主题。 需要注意的是/nodelet_manger/bond是建立nodelet与管理器之间的绑定关系的主题,与实际的模块没有太多的关系。

        $ rosnode list
        /nodelet1
        /nodelet_manager
        /rosout
        /foo
        /nodelet1/out
        /nodelet_manager/bond
        /rosout
        /rosout_agg

通过rostopic工具,我们可以发布一个/foo主题的消息,并监测/nodelet1/out的输出。可以看到通过ROS的工具可以正常使用nodelet,不需要做出额外的更改。 /nodelet1/out总是输出6.1,是系统参数1.1与发布的消息5.0的和。

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

2. Nodelet插件代码分析

接下来我们来看一下加载的nodelet插件Plus的源码。插件类Plus继承自Nodelet类,在其构造函数中没有做什么过多的操作。

        class Plus : public nodelet::Nodelet {
        public:
            Plus() : value_(0) {}

在Plus中定义了三个私有的成员变量。其中_pub为一个消息发布器,_sub为消息订阅器,value_则是求和的一个加数。

        private:
            ros::Publisher pub;
            ros::Subscriber sub;
            double value_;

虚函数onInit是我们运行nodelet的load指令时调用的函数,其存在的意义就是完成对插件的初始化操作。首先通过Nodelet的接口函数getPrivateNodeHandle获取节点句柄, 它提供了当前Nodelet的私有命名空间,也就是我们看到的/nodelet1。然后从参数服务器上获取参数"value"将之赋予私有变量value_。最后发布主题out,并订阅主题in。 在订阅主题的时候绑定了一个回调函数callback,在每次接收到主题in的消息后调用该函数。

        private:
            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);
            }

在回调函数中,将接收的输入值与变量value_相加,将和作为out主题的消息内容发布出去。

        private:
            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);
            }
        };

最后,通过宏定义PLUGINLIB_EXPORT_CLASS告知编译器Plus是一个插件。

        PLUGINLIB_EXPORT_CLASS(nodelet_tutorial_math::Plus, nodelet::Nodelet)

3. roslaunch加载多个Nodelet

roslaunch脚本提供了一种加载多个Nodelet的方法。通过编写launch文件不仅可以方便的配置各个Node的运行环境,也可以轻松的处理Nodelet的复杂关系。 下面是教程nodelet_tutorial_math中的一个launch文件,首先运行了一个manager节点。

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

接着加载一个Nodelet,其中属性args描述了加载环境配置,目标Nodelet就是Plus,并将之与standalone_nodelet绑定。其子标签remap将该Nodelet的输出主题/Plus/out重映射为remapped_output。

            <node pkg="nodelet" type="nodelet" name="Plus" args="load nodelet_tutorial_math/Plus standalone_nodelet" output="screen">
                <remap from="/Plus/out" to="remapped_output"/>
            </node>

下面再加载一个Nodelet,命名为Plus2,其arg属性与加载Plus时一样。主要关注的是rosparam子标签,它是标准的roslaunch加载运行参数的方式,文件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的形式再加载一个Nodelet,命名为Plus3。所谓的standalone的形式,我们看不到显式的Nodelet与管理器之间的绑定关系,实际上这种standalone的形式很少用,大多还是采用上面提到的load的形式。 在其子标签param中定义了Plus3的运行时参数其值为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文件中,将/Plus2/out重映射到/Plus3/in上之后,将出使Plus3输出一个连加的结果。我们可以发布一个/Plus2/in的消息,输入数据为1.0。那么/Plus2/out和/Plus3/out将分别输出11.0和13.5。 运行历程就是,Plus2收到in主题的消息后将输入数据与自身value_相加,然后发布一个/Plus2/out的消息。因为/Plus2/out重映射到了/Plus3/in上,所以Plus3就会以Plus2的输出消息作为输入加和后输出13.5。

    $ rostopic pub /Plus2 std_msgs/Float64 1.0 -r 10
    $ rostopic echo /Plus2/out
    $ rostopic echo /Plus3/out

4. Nodelet的发布

我们已经知道Nodelet本质上就是ROS的一个插件系统,若要让编写的Nodelet模块正常的工作,我们还需要参照ROS插件系统pluginlib的描述, 完成插件的注册工作。

首先,我们需要在CMakeLists.txt中添加编译插件链接库的指令,下面是官方教程中相关的代码片段,通过add_library描述编译对象,用target_link_libraries描述链接关系,add_dependencies则描述了依赖关系。

    add_library(nodelet_math src/plus.cpp)
    target_link_libraries(nodelet_math ${catkin_LIBRARIES})
    if(catkin_EXPORTED_LIBRARIES)
        add_dependencies(nodelet_math ${catkin_EXPORTED_LIBRARIES})
    endif()

然后,需要创建一个xml文件来描述插件的各种属性,包括动态链接库的路径,插件类型,插件基类等。nodelet_tutorial_math中用文件nodelet_math.xml来描述,其内容如下:

        <library path="lib/libnodelet_math">
            <class name="nodelet_tutorial_math/Plus" type="nodelet_tutorial_math::Plus" base_class_type="nodelet::Nodelet">
                <description>A node to add a value and republish.</description>
            </class>
        </library>

最后,在package.xml文件中添加如下的声明,表示包中有一个插件。

        <export>
            <nodelet plugin="${prefix}/nodelet_math.xml"/>
        </export>

5. 总结

Nodelet借助roscpp对于运行与同一个节点中的消息发布订阅机制的优化特点,采用动态加载插件的形式实现了在同一个节点中多个算法模块之间的零拷贝消息传递模式。 这样可以有效提高ROS系统的运行效率,尤其是在有图像、点云等大数据量的应用场景下。




Copyright @ 高乙超. All Rights Reserved. 京ICP备16033081号-1