将ros节点改为同时支持独立节点、nodelet节点格式的详细步骤

在不改变原来代码结构的情况下将原节点封装成同时支持独立节点运行(包含main函数)、nodelet插件形式(不包含main函数)。

目录

1、参考:

2、Nodelet简介

3、修改nodelet节点

3.1. 新建一个nodelet.cpp文件,用于实现nodelet插件程序。

3.2、更改主算法类,使其构造函数支持节点句柄参数传递。

3.3. 更改 main ()函数,

3.4. 在package.xml中对nodelet添加 和 依赖项。

3.5. 编写插件描述符

3.6. 请在包清单package.xml的 部分中添加 项,导出插件包到ROS系统

3.7. 对 CMakeLists.txt 进行必要的更改

3.8、编写launch文件


1、参考:

1、http://wiki.ros.org/nodelet

2、https://blog.csdn.net/xingdou520/article/details/85721779

2、Nodelet简介

Nodelets are designed to provide a way to run multiple algorithms on a single machine, in a single process, without incurring copy costs when passing messages intraprocess. roscpp has optimizations to do zero copy pointer passing between publish and subscribe calls within the same node. To do this nodelets allow dynamic loading of classes into the same node, however they provide simple separate namespaces such that the nodelet acts like a seperate node, despite being in the same process. This has been extended further in that it is dynamically loadable at runtime using pluginlib.

  • 1、nodelet包被设计为在同一个机器,同一个进程中可以零拷贝的运行多个算法。
  • 2nodelet允许动态加载不同的算法类到同一个节点中,并且每一个类都有独立的命名空间。
  • 3、ROS nodelet插件和ROS中普通插件编写流程一样,因为它们都是借助plubinlib来实现插件动态加载,都必须follow pluginlib使用规则.

3、修改nodelet节点

 

3.1. 新建一个nodelet.cpp文件,用于实现nodelet插件程序。

  • 新建example 添加nodelet的继承。
  • 添加virtual void onInit ()函数,并在其中实现自己主算法类的实例化(并通过构造函数的参数见私有句柄和共有句柄传给算法类)。
  • nodelet父类会调用子类的onInit函数初始化子类。
  • 添加PLUGINLIB_EXPORT_CLASS宏。
#include 
#include 
#include 
#include "MobileBase.hpp"

namespace example_ns
{
class example: public nodelet::Nodelet
{
public:
    example () {}
    ~example() {}

private:

    virtual void onInit() {
        node_.reset(new MobileBase(getNodeHandle(), getPrivateNodeHandle())); //传入nodelet的共有句柄、私有句柄、

        printf("\n/****************** onInit OK *********************/\n");

    }
    boost::shared_ptr node_;
};
}
PLUGINLIB_EXPORT_CLASS(jdx::jd_base_node, nodelet::Nodelet);

3.2、更改主算法类,使其构造函数支持节点句柄参数传递。

class MobileBase
{
public:
    MobileBase(ros::NodeHandle &nh, ros::NodeHandle &nh_priv):
        n(nh), pn(nh_priv) //参数列表 传递句柄
    {
    }

private:

    void spin();

*
*
*
*
    ros::NodeHandle n;
    ros::NodeHandle pn;
    boost::shared_ptr spinThread_;
}

3.3. 更改 main ()函数,

如果main函数中存在spin类型的需要循环处理的函数,在主算法类中新建一个进程处理。

main函数:
#include 
#include "MobileBase.hpp"

int main(int argc,char** argv)
{
    ros::init(argc,argv,"mobile_base");
    ros::NodeHandle nh; //共有句柄
    ros::NodeHandle pn("~"); //私有句柄 当前节点 命名空间的句柄
    MobileBase MobileBase(nh, pn);
    // handle callbacks until shut down
    ros::spin();
    return 0;
}

在主算法类中新建spin函数,用于处理循环处理的数据:

void MobileBase::spin()
{
    ros::Rate r(100.0);
    while(ros::ok())
    {
        //循环处理的数据
    }
}

在类中定义线程指针:

boost::shared_ptr spinThread_;

在onInit中新建进程:

spinThread_ = boost::shared_ptr< boost::thread > (new boost::thread(boost::bind(&MobileBase::spin, this)));

3.4. 在package.xml中对nodelet添加依赖项。

nodelet
nodelet

3.5. 编写插件描述符

创建 nodelet_plugin.xml 文件以将 nodelet 定义为插件

mobile_base :为CmakeLists.txtproject定义的名字:


    
        
            mobile_base nede ,communicate with the robot.
        
    

3.6. 请在包清单package.xml的 部分中添加 项,导出插件包到ROS系统

输入的参数为上面创建的插件描述符。


    

3.7. 对 CMakeLists.txt 进行必要的更改

同时生成nodelet插件库文件和节点可执行文件:

find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
nodelet
)

catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS roscpp std_msgs nodelet
)

## Declare a C++ executable
add_executable(${PROJECT_NAME}_node src/main.cpp src/MobileBase.cpp)
add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} )
target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES})

## Declare a C++ library
add_library(${PROJECT_NAME}
src/nodelet.cpp src/MobileBase.cpp
)
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS} )
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES})

3.8、编写launch文件




    
    

    
    

 

你可能感兴趣的:(技术资料,ROS)