nav_core功能包

nav_core功能包包含全局规划器、局部规划器、恢复行为以及相关参数的接口,其它模块的算法需要继承对应的接口实现对应的函数作为插件被move_base调用。主要包含四个接口:

base_global_planner.h 提供全局路径接口
base_local_planner.h 提供局部路径规划接口
recovery_behavior.h 提供恢复行为接口
parameter_magic.h 参数使用检查接口,若使用旧的参数,会发出警告

一、base_global_planner.h

全局路径规划的接口,navigation中调用的所有全局路径规划器插件都要实现的接口。定义了BaseGlobalPlanner基类,包含三个纯虚函数以及虚析构函数,全局路径规划插件实现时要继承重写该接口中的函数,在ros中才能使用。

//计算全局路径,start起点位姿,goal目标点位姿,plan全局路径点,返回值true代表找到有效路径。
 virtual bool makePlan(const geometry_msgs::PoseStamped& start,const geometry_msgs::PoseStamped& goal,  
                                                 std::vector<geometry_msgs::PoseStamped>& plan) = 0; 
 //计算全局路径,,start起点位姿,goal目标点位姿,plan全局路径点,cost全局路径代价,返回值true代表找到有效路径。
 virtual bool makePlan(const geometry_msgs::PoseStamped& start,const geometry_msgs::PoseStamped& goal,             		       
                                                 std::vector<geometry_msgs::PoseStamped>& plan,double& cost)
 {
        cost = 0; //全局路径代价为0,和上面计算全局路径函数一致
        return makePlan(start, goal, plan);
  }
  //初始化函数,name是全局规划器名称,costmap_ros指针,指向代价地图ROS封装类
  virtual void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) = 0;
  

在global_planner包中的planner_core.h中继承该基类

class GlobalPlanner : public nav_core::BaseGlobalPlanner {
                      ......
}

在planner_core.cpp 中添加插件,同时实现函数。

PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)

具体实现在全局规划器global_planner中会重新补充。

二、base_local_planner.h

局部路径规划器的接口,navigation中调用的所有局部路径规划器插件都要实现的接口,定义BaseLocalPlanner基类,包含四个纯虚函数以及虚析构函数。

// 根据机器人当前的位置、朝向以及机器人速度,计算下发给底盘的速度,返回值true表示找到有效路径,即速度有效
      virtual bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel) = 0;
//是否到达目标点,返回值true表示到达
      virtual bool isGoalReached() = 0;
//更新设置跟随的全局路径,plan是传给局部路径的全局路径点,返回值true表示更新成功。
      virtual bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan) = 0;
//初始化函数, name局部路径规划器名称,tf 指针,进行tf坐标转换的指针,costmap_ros指针,指向代价地图ROS封装类
      virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) = 0;

同样的,在局部路径规划器中继承该类,在dwa_local_planner包中的dwa_planner_ros.h继承:

  class DWAPlannerROS : public nav_core::BaseLocalPlanner {
                       ......
}

在dwa_planner_ros.cpp中注册添加该插件,进行函数实现

PLUGINLIB_EXPORT_CLASS(dwa_local_planner::DWAPlannerROS, nav_core::BaseLocalPlanner)

具体实现在局部规划器中会重新补充。

三、recovery_behavior.h

恢复行为接口, 提供恢复行为的接口,navigation中调用的所有恢复行为模块都要实现这个接口.,定义RecoveryBehavior基类,含有两个纯虚函数以及析构函数。

//初始化,name恢复行为的名称,tf 指针,transform listener 坐标变换的指针, global_costmap 指向 global_costmap 的指针,local_costmap 指向 local_costmap 的指针
      virtual void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* global_costmap,
                                                   costmap_2d::Costmap2DROS* local_costmap) = 0;
//执行恢复行为的函数---主要
       virtual void runBehavior() = 0;

在move_slow_and_clear、rotate_recovery、clear_costmap_recovery中公有继承该基类

  class MoveSlowAndClear : public nav_core::RecoveryBehavior
{
                ......
}
class RotateRecovery : public nav_core::RecoveryBehavior
{
                     ......
}
  class ClearCostmapRecovery : public nav_core::RecoveryBehavior {
               ......
}

在对应的实现中注册插件,实现在ros中调用

PLUGINLIB_EXPORT_CLASS(move_slow_and_clear::MoveSlowAndClear, nav_core::RecoveryBehavior)
PLUGINLIB_EXPORT_CLASS(rotate_recovery::RotateRecovery, nav_core::RecoveryBehavior)
PLUGINLIB_EXPORT_CLASS(clear_costmap_recovery::ClearCostmapRecovery, nav_core::RecoveryBehavior)

四、parameter_magic.h

加载参数时用到旧的参数名提示修改


总结

本文对nav_core包进行了简单的分析,提供ROS接口,使得全局规划、局部规划等以插件的形式加载到ros中,便于其在ros中使用。

Logo

魔乐社区(Modelers.cn) 是一个中立、公益的人工智能社区,提供人工智能工具、模型、数据的托管、展示与应用协同服务,为人工智能开发及爱好者搭建开放的学习交流平台。社区通过理事会方式运作,由全产业链共同建设、共同运营、共同享有,推动国产AI生态繁荣发展。

更多推荐