pluginlib
pluginlib
简介
-
ROS Pluginlib是ROS提供的一个功能包,用于制作和加载ros plugin。ros plugin本质上是将C++类通过pluginlib进行封装,编译为动态库(.so文件)。再通过pluginlib提供的接口在主程序中实现运行时加载plugin
-
ROS中的插件(plugin)就是可以动态加载的扩展功能类,在ROS框架中,加载和卸载插件通过pluginlib功能包实现,开发者在使用插件的时候不需要考虑其链接位置,只需要直接注册到pluginlib中
-
pluginlib利用了C++多态的特性,不同的插件只要使用统一的接口,就可以替换使用,用户在使用过程中也不需要修改代码或者重新编译,选择需要使用的插件即可扩展相应的功能
创建基类
这里创建一个多边形类RegularPolygon(polygon_base.h),基于命名空间polygon_base。此多边形类主要有两个接口函数,initialize()
函数,用于初始化边长,area()
函数,用于计算多边形面积,这两个函数都是virtual类型,也就是可以在子类中重写的,以实现多态
#pragma once
namespace polygon_base
{
class RegularPolygon
{
public:
//pluginlib要求构造函数不能带有参数,所以定义initialize来完成需要初始化的工作
virtual void initialize(double side_length) = 0;
//计算面积的接口函数
virtual double area() = 0;
virtual ~RegularPolygon(){}
protected:
RegularPolygon(){}
};
};
创建plugin类
创建三角形类Triangle和四边形类Square(polygon_plugins.h),均继承了多边形类RegularPolygon,子类中重写initialize()
和area()
,实现了不同的功能
#pragma once
#include <pluginlib_tutorials/polygon_base.h>
#include <cmath>
namespace polygon_plugins
{
class Triangle : public polygon_base::RegularPolygon
{
public:
Triangle() {};
// 初始化边长
void initialize(double side_length)
{
side_length_ = side_length;
}
double area()
{
return 0.5 * side_length_ * getHeight();
}
// Triangle类自己的接口
double getHeight()
{
return sqrt((side_length_ * side_length_) - ((side_length_ / 2) * (side_length_ / 2)));
}
private:
double side_length_{};
};
class Square : public polygon_base::RegularPolygon
{
public:
Square() {};
// 初始化边长
void initialize(double side_length)
{
side_length_ = side_length;
}
double area()
{
return side_length_ * side_length_;
}
private:
double side_length_{};
};
};
注册插件
接下来创建一个cpp文件(polygon_plugins.cpp)来注册插件。此cpp文件将普通C++类制作为ros plugin,通过宏PLUGINLIB_EXPORT_CLASS()
实现,此宏有两个参数,第一个参数为子类全名,第二个参数为基类全名,全名是包含了命名空间
//包含pluginlib的头文件,使用pluginlib的宏来注册插件
#include <pluginlib/class_list_macros.h>
#include <pluginlib_tutorials/polygon_base.h>
#include <pluginlib_tutorials/polygon_plugins.h>
//注册插件,宏参数:plugin的实现类,plugin的基类
PLUGINLIB_EXPORT_CLASS(polygon_plugins::Triangle, polygon_base::RegularPolygon);
PLUGINLIB_EXPORT_CLASS(polygon_plugins::Square, polygon_base::RegularPolygon);
制作插件描述文件
在功能包根目录下添加polygon_plugins.xml文件
<library path="lib/libpluginlib_tutorials">
<class type="polygon_plugins::Triangle" base_class_type="polygon_base::RegularPolygon">
<description>This is a triangle plugin.</description>
</class>
<class type="polygon_plugins::Square" base_class_type="polygon_base::RegularPolygon">
<description>This is a square plugin.</description>
</class>
</library>
此插件描述文件,描述了插件信息,即插件库文件的位置,插件全名以及插件父类全名。在节点运行时,ROS是通过插件描述文件定位并加载插件的
导出插件
导出插件,即是通过包描述文件package.xml,导出插件描述文件,使得其他节点可以使用本包提供的插件,在package.xml中添加下边的两行代码:
<export>
<pluginlib_tutorials plugin="${prefix}/polygon_plugins.xml" />
</export>
使用插件类
#include <ros/ros.h>
#include <pluginlib/class_loader.h>
#include <pluginlib_tutorials/polygon_base.h>
int main(int argc, char** argv)
{
ros::init(argc, argv, "plugin_test");
ros::NodeHandle n;
// 使用pluginlib中的ClassLoader模板类,创建ros plugin加载句柄poly_loader。此模板类的数据类型为基类类型
// 需要传入两个参数,一个是基类所在的包,一个是基类全名
pluginlib::ClassLoader<polygon_base::RegularPolygon> poly_loader("pluginlib_tutorials", "polygon_base::RegularPolygon");
try
{
// 通过句柄poly_loader,实例化插件类对象triangle
boost::shared_ptr<polygon_base::RegularPolygon> triangle = poly_loader.createInstance("polygon_plugins::Triangle");
triangle->initialize(10.0);
boost::shared_ptr<polygon_base::RegularPolygon> square = poly_loader.createInstance("polygon_plugins::Square");
square->initialize(10.0);
ROS_INFO("Triangle area: %.2f", triangle->area());
ROS_INFO("Square area: %.2f", square->area());
ROS_INFO("OK");
}
catch(pluginlib::PluginlibException& ex)
{
ROS_ERROR("The plugin failed to load for some reason. Error: %s", ex.what());
}
return 0;
}
修改CMakeLists.txt
修改CMakeLists.txt:
cmake_minimum_required(VERSION 3.10)
project(pluginlib_tutorials)
## Find catkin dependencies
find_package(catkin REQUIRED COMPONENTS
pluginlib
roscpp
)
## Find Boost (headers only)
find_package(Boost REQUIRED)
## Define catkin exports
catkin_package(
INCLUDE_DIRS include
LIBRARIES pluginlib_tutorials
CATKIN_DEPENDS
pluginlib
roscpp
DEPENDS Boost
)
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
## pluginlib_tutorials library
add_library(polygon_plugins src/polygon_plugins.cpp)
target_link_libraries(polygon_plugins ${catkin_LIBRARIES})
## polygon_loader executable
add_executable(polygon_loader src/polygon_loader.cpp)
target_link_libraries(polygon_loader ${catkin_LIBRARIES})
include_directories()
中include指的是类定义所在的目录。add_library()
将指定源程序编译为库文件,默认是动态库文件(.so)