move_base的心脏——nav_core
1. nav_core
nav_core功能包中包括navigation_stack的关键接口。所有的路径规划算法和恢复行为都使用插件形式继承这些接口来实现的。
后续几章会重点详解GlobalPlanner和LocalPlanner.
2. BaseGlobalPlanner API
nav_core::BaseGlobalPlanner
微导航提供全局路径规划接口。所有的路径规划算法都会写成move_base节点的插件,这些插件都要继承于这个接口。接下来详细说下接口。
#ifndef NAV_CORE_BASE_GLOBAL_PLANNER_H
#define NAV_CORE_BASE_GLOBAL_PLANNER_H
#include <geometry_msgs/PoseStamped.h>
#include <costmap_2d/costmap_2d_ros.h>
namespace nav_core {
class BaseGlobalPlanner{
public:
virtual bool makePlan(const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan) = 0;
virtual bool makePlan(const geometry_msgs::PoseStamped& start,
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan,
double& cost)
{
cost = 0;
return makePlan(start, goal, plan);
}
virtual void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) = 0;
virtual ~BaseGlobalPlanner(){
}
protected:
BaseGlobalPlanner(){
}
};
}; // namespace nav_core
#endif // NAV_CORE_BASE_GLOBAL_PLANNER_H
3. BaseLocalPlanner API
#ifndef NAV_CORE_BASE_LOCAL_PLANNER_H
#define NAV_CORE_BASE_LOCAL_PLANNER_H
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Twist.h>
#include <costmap_2d/costmap_2d_ros.h>
#include <tf2_ros/buffer.h>
namespace nav_core {
class BaseLocalPlanner{
public:
// 给定机器人位置朝向和速度,求传到底盘的速度指令
virtual bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel) = 0;
virtual bool isGoalReached() = 0;
// 设置局部planner要跟随的轨迹(与全局路径规划的联系)
virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan) = 0;
// tf: tf_listener的指针
virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) = 0;
virtual ~BaseLocalPlanner(){
}
protected:
BaseLocalPlanner(){
}
};
}; // namespace nav_core
#endif // NAV_CORE_BASE_LOCAL_PLANNER_H
4. 分析
- 全局路径规划不需要tf,直接给定start和goal,输出plan即可
- 局部路径规划需要依赖全局路径规划输出的plan,同时依赖tf,最终输出速度指令交给底盘进行控制