1. 程式人生 > >自定義nodelet外掛

自定義nodelet外掛

參考連結:
http://wiki.ros.org/nodelet
http://wiki.ros.org/nodelet/Tutorials/Running a nodelet
http://wiki.ros.org/nodelet/Tutorials/Porting nodes to nodelets
https://blog.csdn.net/zyh821351004/article/details/52143309

ROS的資料通訊是以XML-RPC的方式,在graph結構中以topic,service和param的方式傳輸資料,天生的資料互動存在一定的延時和阻塞。Nodelet 包就是改善這一狀況設計的, 使得多個演算法執行在同一個過程中,並且演算法間資料傳輸無需拷貝就可實現。 詳見http://wiki.ros.org/nodelet。 簡單的講就是可以將以前啟動的多個node捆綁在一起manager,使得同一個manager裡面的topic的資料傳輸更快,資料通訊中roscpp採用boost shared pointer方式進行publish呼叫,實現zero copy。

以下為本人自己在學習相關資料,自己做的一個測試用例,供參考。
1 建立工作空間
makedir nodelet_ws/src

2 建立nodelet_test包
catkin_create_pkg nodelet_test roscpp std_msgs nodelet

3 建立nodelet_test/src/math_plus.cpp檔案
math_plus.cpp

#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include <ros/ros.h>
#include <std_msgs/Float64.h>

namespace math_test
{
    /* code */
    class math_plus: public nodelet::Nodelet
    {
    public:
        math_plus()
        {

        }
        virtual ~math_plus()
        {

        }
    
    private:
        virtual void onInit()
        {
            ros::NodeHandle& private_nh = getPrivateNodeHandle();
            private_nh.getParam("value", value_);
            plus_result_pub_ = private_nh.advertise<std_msgs::Float64>("out", 10);
            plus_param_sub_ = private_nh.subscribe("in", 10, &math_plus::plus_process_callback, this);
        }

        void plus_process_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);
            plus_result_pub_.publish(output);
        }

    private:
        ros::Publisher plus_result_pub_;
        ros::Subscriber plus_param_sub_;
        double value_;
    };
}

PLUGINLIB_EXPORT_CLASS(math_test::math_plus, nodelet::Nodelet);

math_plus.cpp解析:
(1)通過 plus_param_sub_ = private_nh.subscribe(“in”, 10, &math_plus::plus_process_callback, this)訂閱名為math_plus/in topic的資料
(2)與通過引數伺服器(private_nh.getParam(“value”, value_))獲取到的引數value_進行相加
(3)將相加後的結果通過plus_result_pub_.publish(output)以topic的形式釋出出去

外掛註冊:
PLUGINLIB_EXPORT_CLASS(math_test::math_plus, nodelet::Nodelet);

4 math_plus_plugin.xml

<library path="lib/libmath_plus">
    <class name="nodelet_test/math_plus" type="math_test::math_plus" base_class_type="nodelet::Nodelet">
        <description>
            A node to add a value and republish.
        </description>
    </class>
</library>

5 CMakeList.txt

cmake_minimum_required(VERSION 2.8.3)
project(nodelet_test)

find_package(catkin REQUIRED COMPONENTS
  nodelet
  roscpp
  std_msgs
)

catkin_package(
)

include_directories(
  include ${catkin_INCLUDE_DIRS}
  ${catkin_INCLUDE_DIRS}
)

add_library(math_plus
  src/math_plus.cpp
)
add_dependencies(math_plus ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(math_plus
  ${catkin_LIBRARIES}
)

6 package.xml

<?xml version="1.0"?>
<package format="2">
  <name>nodelet_test</name>
  <version>0.0.0</version>
  <description>The nodelet_test package</description>

  <maintainer email="[email protected]">zyn</maintainer>
  <license>TODO</license>
  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>nodelet</build_depend>
  <build_depend>roscpp</build_depend>
  <build_depend>std_msgs</build_depend>
  <build_export_depend>nodelet</build_export_depend>
  <build_export_depend>roscpp</build_export_depend>
  <build_export_depend>std_msgs</build_export_depend>
  <exec_depend>nodelet</exec_depend>
  <exec_depend>roscpp</exec_depend>
  <exec_depend>std_msgs</exec_depend>

  <!-- The export tag contains other, unspecified, tags -->
  <export>
    <!-- Other tools can request additional information be placed here -->
    <nodelet plugin="${prefix}/math_plus_plugin.xml"/>
  </export>
</package>

7 launch檔案
math_plus_launch.launch

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

    <node pkg="nodelet" type="nodelet" name="math_plus" args="load nodelet_test/math_plus math_plus_manage" output="screen">
        <param name="value" type="double" value="10"/>
    </node>

</launch>

步驟 3 4 5 6 7之間的聯絡:
(1)步驟4 中的libmath_plus 由步驟5 中的add_library(math_plus src/math_plus.cpp)生成
(2)步驟4 中 的 type 和 base_class_type 由步驟3中PLUGINLIB_EXPORT_CLASS(math_test::math_plus, nodelet::Nodelet)確定
(3)步驟6 中 的math_plus_plugin.xml 為步驟 4 中建立的檔案
(4)步驟7 中 的nodelet_test/math_plus 與步驟4 中的 class name=“nodelet_test/math_plus” 相對應
(5)步驟7 中的 為步驟3 中的 value引數提供資料,資料值為double型數值10

math_plus_launch.launch檔案:
(1)啟動兩個notelet節點,但引數不同分別為args="manager"和args=“load nodelet_test/math_plus math_plus_manage”,可以淺顯的認為引數manager對應的節點充當管理層,另一個或多個節點充當被管理者
(2)引數args=“load nodelet_test/math_plus math_plus_manage” 中,
load :載入
nodelet_test/math_plus:外掛類名稱
math_plus_manage:外掛所屬的管理層名稱

nodelet可以同時建立多個管理層,可以根據需求將nodelet分配到對應的manage層中,如
example.launch

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

    <node pkg="nodelet" type="nodelet" name="math_plus" args="load nodelet_test/math_plus math_plus_manage" output="screen">
        <param name="value" type="double" value="10"/>
    </node>

    <node pkg="nodelet" type="nodelet" name="math_plus1" args="load nodelet_test/math_plus math_plus_manage" output="screen">
    </node>
    <node pkg="nodelet" type="nodelet" name="math_plus2" args="load nodelet_test/math_plus math_plus_manage" output="screen">
    </node>
    <node pkg="nodelet" type="nodelet" name="math_plus3" args="load nodelet_test/math_plus math_plus_manage" output="screen">
    </node>

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

    <node pkg="nodelet" type="nodelet" name="math_plus4" args="load nodelet_test/math_plus math_plus_manage_2" output="screen">
    </node>
    <node pkg="nodelet" type="nodelet" name="math_plus5" args="load nodelet_test/math_plus math_plus_manage_2" output="screen">
    </node>

    <node pkg="nodelet" type="nodelet" name="math_plus6" args="standalone nodelet_test/math_plus" output="screen">
    </node>

</launch>

example.launch中表明,math_plus、math_plus1、math_plus2、math_plus3對應的nodelet所屬manager為math_plus_manage,math_plus4、math_plus5所屬manager為math_plus_manage_2,test6獨立存在,他們之間的資料互動按manager進行劃分,示意如下:
在這裡插入圖片描述

8 執行測試
(1)啟動nodelet
roslaunch nodelet_test math_plus_launch.launch

(2)釋出/math_plus/in topic 數值為 1
rostopic pub -r 1 /math_plus/in std_msgs/Float64 1

(3)rostopic echo /math_plus/out檢視輸出資料

[email protected]:~/zyn_test/nodelet_ws$  rostopic echo /math_plus/out
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---
data: 11.0
---

launch檔案中的引數值為10, 釋出的topic資料為1 ,相加後的結果為 11