Navigation包 Global_planner全局路径规划源码详细解析

11 篇文章 34 订阅
5 篇文章 0 订阅

学习总结,如有错误欢迎指正!

一丶plan_node.cpp

从程序入口开始,首先在plan_node.cppmain函数中,初始化了全局路径规划器。

    costmap_2d::Costmap2DROS lcr("costmap", buffer);
    global_planner::PlannerWithCostmap pppp("planner", &lcr);

在函数PlannerWithCostmap中设置了两种调用makePlan的路径:

PlannerWithCostmap::PlannerWithCostmap(string name, Costmap2DROS* cmap) :
        GlobalPlanner(name, cmap->getCostmap(), cmap->getGlobalFrameID()) {
    ros::NodeHandle private_nh("~");
    cmap_ = cmap;
    make_plan_service_ = private_nh.advertiseService("make_plan", &PlannerWithCostmap::makePlanService, this);
    pose_sub_ = private_nh.subscribe<rm::PoseStamped>("goal", 1, &PlannerWithCostmap::poseCallback, this);
}
  • 1.通过make_plan服务
    req.start.header.frame_id = "map";
    req.goal.header.frame_id = "map";
    bool success = makePlan(req.start, req.goal, path);
  • 2.通过goal回调函数
    //得到当前机器人在MAP中的位置
    cmap_->getRobotPose(global_pose);
    makePlan(global_pose, *goal, path);

getRobotPose函数中,通过tf_.transform(robot_pose, global_pose, global_frame_);函数,默认将机器人posebase_link转换到map坐标系下,可通过参数设置。得到起始点和目标点传入到makePlan中。

二丶 planner_core.cpp

//register this planner as a BaseGlobalPlanner plugin
PLUGINLIB_EXPORT_CLASS(global_planner::GlobalPlanner, nav_core::BaseGlobalPlanner)

global_planner 是基类nav_core :: BaseGlobalPlanner的一个插件子类

首先在构造函数中需要初始化GlobalPlanner,在initialize中对一些参数进行赋值。

GlobalPlanner::GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) :
        GlobalPlanner() {
    //initialize the planner
    initialize(name, costmap, frame_id);
}

当调用makePlan时,首先就是判断是否已经被初始化:

    // code line 221~225  makePlan()
    if (!initialized_) {
        ROS_ERROR(
                "This planner has not been initialized yet, but it is being used, please call initialize() before use");
        return false;
    }m

初始化完成之后,清除之前规划的Plan,以防万一。然后检查起点和终点是否在我们所需要的坐标系下,一般在map系下。

    //clear the plan, just in case , code line 227  makePlan()
    plan.clear();
    if (goal.header.frame_id != global_frame) {...}
    if (start.header.frame_id != global_frame){...}

将世界坐标系的点(map 坐标系)转换成图像坐标系(图像左下角)下的点(以像素表示)

if (!costmap_->worldToMap(wx, wy, goal_x_i, goal_y_i)) {
   ROS_WARN_THROTTLE(1.0,"The goal sent to the global planner is off the global costmap. Planning will always fail to this goal.");
   return false;
}

Costmap2DGlobalPlanner中都有实现worldToMap,其实都是一样的,在GlobalPlanner中则需要通过调用Costmap2D来获取局部地图的起始点和分辨率,而在Costmap2D则可以直接使用全局变量。

bool Costmap2D::worldToMap(double wx, double wy, unsigned int& mx, unsigned int& my) const
{
  if (wx < origin_x_ || wy < origin_y_)
    return false;
  mx = (int)((wx - origin_x_) / resolution_);
  my = (int)((wy - origin_y_) / resolution_);
  if (mx < size_x_ && my < size_y_)
    return true;
  return false;
}

old_navfn_behavior_ 作为一种旧式规划行为:

  1. The start of the path does not match the actual start location.
  2. The very end of the path moves along grid lines.
  3. All of the coordinates are slightly shifted by half a grid cell

现在在worldToMap所使用的convert_offset_ = 0

接下来将机器人Robot所在的位置,在costmap中设置成free,当前位置不可能是一个障碍物。
即在clearRobotCell()函数中:mxmy即当前机器人位置。

costmap_->setCost(mx, my, costmap_2d::FREE_SPACE);

设置规划地图边框:outlineMap,此函数由参数outline_map_决定。
根据costmap跟起始终止点计算网格的potential,计算的算法有两种:DijkstraA*,具体算法便不再讨论,资料很多。
当提取到plan之后,调用getPlanFromPotential,把path转换变成geometry_msgs::PoseStamped数据类型。

 if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) {
      //make sure the goal we push on has the same timestamp as the rest of the plan
      geometry_msgs::PoseStamped goal_copy = goal;
      goal_copy.header.stamp = ros::Time::now();
      plan.push_back(goal_copy);
  } 

此时便得到所需要的路径plan,最终调用OrientationFilter平滑之后发布出去。

    orientation_filter_->processPath(start, plan);
  • 9
    点赞
  • 40
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 4
    评论
navigation2/smac_planner_lattice是ROS2的一个插件,用于路径规划和导航。下面是对其源码的简要解析。 首先介绍一下源码的目录结构。smac_planner_lattice含了几个主要的文件夹和文件。config文件夹含了一些配置文件,可以在其中进行一些参数的设置。include文件夹含了一些头文件,这些头文件定义了插件的一些类和函数。src文件夹含了插件的源代码文件,其中括了插件的主要逻辑。launch文件夹含了一些launch文件,用于启动插件。scripts文件夹含了一些辅助的脚本文件。test文件夹含了一些测试文件和测试用例。 在源代码的主要逻辑部分,主要含了几个类和函数。其中的Planner类是插件的核心类,它实现了路径规划器的主要功能。首先,它会根据收到的地图、起点和终点等信息进行初始化。然后,它会使用一些算法来搜索最佳路径,其中括了离散Lattice规划算法。在搜索过程中,它会考虑一些约束,例如机器人的最大速度、转弯半径等。最后,它会生成一条可行的路径,并将其发布出去。 除了Planner类之外,还有一些辅助的类和函数。例如,CollisionChecker类用于检测路径上是否有障碍物。Costmap类用于处理和更新地图信息。MotionValidator类用于验证运动的合法性。这些类和函数共同协作,实现了路径规划和导航的功能。 总结来说,navigation2/smac_planner_lattice是一个用于路径规划和导航的ROS2插件。它的源码含了一些关键的类和函数,通过使用一些算法和约束来计算并生成一条可行的路径。这个插件在ROS2导航堆栈中起到了重要的作用,可以帮助机器人在复杂环境中完成自主导航。

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

秃头队长

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值