ros自定义全局路径规划器并内置到ros工作空间
做个正直的人
最近做移动机器人的运动规划,需要用到分层自适应路径规划算法。ROS内部已经集成了多种全局路径规划器(BaseGlobalPlanner)和局部路径规划器(BaseLocalPlanner),包括用A*算法、Dijstra算法、DWA动态窗口法等。这些都封装在ros的move_base节点中。一开始我想自己实现一个move_base节点,后来想了想,还是算了吧。搞不赢。
所以就用插件的形式,做了一个全局路径规划器的插件(plugin),这样就可以用ros原本的导航框架了。省下不小的气力。
首先应该明白,我们自定义的全局路径规划器必须遵守ROS的nav_core::BaseGlobalPlanner C++ interface规范,这是ros的一套全局路径规划器都必须遵守的C++接口规范。其实说白了,就是你的规划器必须继承自nav_core::BaseGlobalPlanner 类,否则ROS是不认的。
1、定义头文件
为了方便,我们可以直接拿carrot_planner规划器的头文件来用,先搭起一个架子来。等到具体实现自己的算法的时候对头文件进行具体编写。说实话,如果我们还没有实现自己的规划算法,我又怎么会直到自己的头文件应该怎么写呢?应该声明哪些函数、哪些变量呢?
比如我们把我们的global_planner.h文件写成这个样子
/** include the libraries you need in your planner here */
/** for global path planner interface */
#include <ros/ros.h>
#include <costmap_2d/costmap_2d_ros.h>
#include <costmap_2d/costmap_2d.h>
#include <nav_core/base_global_planner.h>
#include <geometry_msgs/PoseStamped.h>
#include <angles/angles.h>
#include <base_local_planner/world_model.h>
#include <base_local_planner/costmap_model.h>
using std::string;
#ifndef GLOBAL_PLANNER_CPP
#define GLOBAL_PLANNER_CPP
namespace global_planner {
class GlobalPlanner : public nav_core::BaseGlobalPlanner {
public:
GlobalPlanner();
GlobalPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
/** overridden classes from interface nav_core::BaseGlobalPlanner **/
void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
bool makePlan(const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal,
std::vector<geometry_msgs::PoseStamped