【ROS-Navigation】Costmap2D代价地图源码解读-膨胀层InflationLayer


记录学习阅读ROS Navigation源码的理解,本文为Costmap2D代价地图源码学习记录,以文字总结、绘制结构图说明、代码注释为主。仍在学习过程中,有错误欢迎指正,共同进步。

InflationLayer没有自身的栅格地图要维护,直接在主地图上进行操作,它根据膨胀参数设置用来膨胀的“参考矩阵”,并在主地图上从障碍物出发,不断传播更新,完成对整个地图障碍的膨胀,等效于完成一个由“将机器人视为一个点”到“考虑机器人本身的足迹”的转变过程,防止因为忽视了足迹而碰上障碍。



【结构示意图】

在这里插入图片描述



【相关文件】

  • costmap_2d/src/costmap_2d_ros.cpp
  • costmap_2d/src/costmap_2d.cpp
  • costmap_2d/src/layered_costmap.cpp
  • costmap_2d/src/costmap_layer.cpp
  • costmap_2d/plugins/static_layer.cpp
  • costmap_2d/plugins/obstale_layer.cpp
  • costmap_2d/plugins/inflation_layer.cpp

本篇记录对InflationLayer类的阅读和理解。



【代码分析】

InflationLayer类

–目录–

InflationLayer::onInitialize | 初始化
InflationLayer::computeCaches & computeCosts | 参考矩阵
InflationLayer::updateBounds | 更新膨胀地图边界
InflationLayer::updateCosts | 更新膨胀地图代价
InflationLayer::enquene | “传播”

<1> 初始化 InflationLayer::onInitialize

这个函数没什么特别的,最重要的工作是调用了类内的matchSize函数。

void InflationLayer::onInitialize()
{
  {
    boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
    ros::NodeHandle nh("~/" + name_), g_nh;
    current_ = true;
    if (seen_)
      delete[] seen_;
    seen_ = NULL;
    seen_size_ = 0;
    need_reinflation_ = false;

    dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>::CallbackType cb = boost::bind(
        &InflationLayer::reconfigureCB, this, _1, _2);

    if (dsrv_ != NULL){
      dsrv_->clearCallback();
      dsrv_->setCallback(cb);
    }
    else
    {
      dsrv_ = new dynamic_reconfigure::Server<costmap_2d::InflationPluginConfig>(ros::NodeHandle("~/" + name_));
      dsrv_->setCallback(cb);
    }
  }

  matchSize();
}

由于InflationLayer没有继承Costmap2D,所以它和静态地图与障碍地图这两层不同,它没有属于自己的栅格地图要维护,所以matchSize函数自然不需要根据主地图的参数来调节本层地图。这个函数先获取主地图的分辨率,接着调用cellDistance函数,这个函数可以把global系以米为单位的长度转换成以cell为单位的距离,故获得了地图上的膨胀参数cell_inflation_radius_。

接下来调用computeCaches函数,完成两个“参考矩阵”的填充,内容后述。

最后根据主地图大小创建seen_数组,它用于标记cell是否已经过计算。

void InflationLayer::matchSize() { 
    boost::unique_lock <boost::recursive_mutex > lock(*inflation_access_);  
    costmap_2d::Costmap2D* costmap = layered_costmap_->getCostmap();  
    resolution_ = costmap->getResolution();
    cell_inflation_radius_ = cellDistance(inflation_radius_);   
    
    computeCaches();
    unsigned int size_x = costmap->getSizeInCellsX(), size_y = costmap->getSizeInCellsY();
    
    if (seen_)
       delete[] seen_;
    seen_size_ = size_x * size_y;
    seen_ = new bool[seen_size_]; 
    } 

<2> 参考矩阵 InflationLayer::computeCaches & computeCosts

这里称cached_distances_和cached_costs_为参考矩阵,因为它们是后续膨胀计算的参照物。

由于是基于膨胀参数来设置参考矩阵的,所以当cell_inflation_radius_==0,直接返回。

第二个if结构是用来初始化这两个参考矩阵的,只在第一次进入时执行,它们的大小都是(cell_inflation_radius_ + 2)x(cell_inflation_radius_ + 2),设置cached_distances_矩阵的元素值为每个元素到(0,0)点的三角距离。

最后调用computeCosts函数将cached_distances_矩阵“翻译”到cached_costs_矩阵。

void InflationLayer::computeCaches()
{
  if (cell_inflation_radius_ == 0)
    return;
  
  if (cell_inflation_radius_ != cached_cell_inflation_radius_)
  {
    deleteKernels();
    //成本和代价的数组“行”大小都是cell_inflation_radius_+2
    cached_costs_ = new unsigned char*[cell_inflation_radius_ + 2];
    cached_distances_ = new double*[cell_inflation_radius_ + 2];

    for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
    {
      //成本和代价的数组“列”大小也是cell_inflation_radius_+2
      cached_costs_[i] = new unsigned char[cell_inflation_radius_ + 2];
      cached_distances_[i] = new double[cell_inflation_radius_ + 2];
      for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
      {
        //每个元素的值即为它到[0][0]点的三角距离
        cached_distances_[i][j] = hypot(i, j);
      }
    }
    //设置cached_cell_inflation_radius_,所以第二次再进入的时候就不再执行这个if结构
    cached_cell_inflation_radius_ = cell_inflation_radius_;
  }

  for (unsigned int i = 0; i <= cell_inflation_radius_ + 1; ++i)
  {
    for (unsigned int j = 0; j <= cell_inflation_radius_ + 1; ++j)
    {
      cached_costs_[i][j] = computeCost(cached_distances_[i][j]);
    }
  }
}
  • 若距离为0,即(0,0)点,则设置cached_costs_上的值为LETHAL_OBSTACLE(254),表示为障碍物本身;
  • 若距离(转换到global系后)≤ 机器人足迹内切圆半径,设置值为INSCRIBED_INFLATED_OBSTACLE(253),即由于机器人有体积造成的障碍物膨胀;
  • 若机器人足迹内切圆半径 < 距离(转换到global系后)≤ cell_inflation_radius_,则以距离远近为比例(指数型)设置值。

所以,最终cached_costs_上,原点值为254,原点到机器人足迹内切圆半径范围内为253,其余按比例下降(指数型,近处骤降),cell_inflation_radius_(膨胀参数)以外没有值。

  inline unsigned char computeCost(double distance) const
  {
    unsigned char cost = 0;
    if (distance == 0)
      cost = LETHAL_OBSTACLE;
    else if (distance * resolution_ <= inscribed_radius_)
      cost = INSCRIBED_INFLATED_OBSTACLE;
    else
    {
      // make sure cost falls off by Euclidean distance
      double euclidean_distance = distance * resolution_;
      double factor = exp(-1.0 * weight_ * (euclidean_distance - inscribed_radius_));
      cost = (unsigned char)((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
    }
    return cost;
  }

cached_costs_示意图:
在这里插入图片描述

<3> 更新膨胀地图边界 InflationLayer::updateBounds

need_reinflation_默认false,更新bound这里和其他两层的主要区别是,膨胀层在传入的bound的值的基础上,通过inflation_radius_再次扩张。

void InflationLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
                                           double* min_y, double* max_x, double* max_y)
{
  if (need_reinflation_)
  {
    last_min_x_ = *min_x;
    last_min_y_ = *min_y;
    last_max_x_ = *max_x;
    last_max_y_ = *max_y;
    // For some reason when I make these -<double>::max() it does not
    // work with Costmap2D::worldToMapEnforceBounds(), so I'm using
    // -<float>::max() instead.
    *min_x = -std::numeric_limits<float>::max();
    *min_y = -std::numeric_limits<float>::max();
    *max_x = std::numeric_limits<float>::max();
    *max_y = std::numeric_limits<float>::max();
    need_reinflation_ = false;
  }
  else
  {
    double tmp_min_x = last_min_x_;
    double tmp_min_y = last_min_y_;
    double tmp_max_x = last_max_x_;
    double tmp_max_y = last_max_y_;
    last_min_x_ = *min_x;
    last_min_y_ = *min_y;
    last_max_x_ = *max_x;
    last_max_y_ = *max_y;
    *min_x = std::min(tmp_min_x, *min_x) - inflation_radius_;
    *min_y = std::min(tmp_min_y, *min_y) - inflation_radius_;
    *max_x = std::max(tmp_max_x, *max_x) + inflation_radius_;
    *max_y = std::max(tmp_max_y, *max_y) + inflation_radius_;
  }
}

<4> 更新膨胀地图代价 InflationLayer::updateCosts

用指针master_array指向主地图,并获取主地图的尺寸,确认seen_数组被正确设置。

void InflationLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
{
  boost::unique_lock < boost::recursive_mutex > lock(*inflation_access_);
  if (!enabled_ || (cell_inflation_radius_ == 0))
    return;
    
  //循环前膨胀层的list应该为空
  ROS_ASSERT_MSG(inflation_cells_.empty(), "The inflation list must be empty at the beginning of inflation");
  
  unsigned char* master_array = master_grid.getCharMap();
  unsigned int size_x = master_grid.getSizeInCellsX(), size_y = master_grid.getSizeInCellsY();

  if (seen_ == NULL) {
    ROS_WARN("InflationLayer::updateCosts(): seen_ array is NULL");
    seen_size_ = size_x * size_y;
    seen_ = new bool[seen_size_];
  }
  else if (seen_size_ != size_x * size_y)
  {
    ROS_WARN("InflationLayer::updateCosts(): seen_ array size is wrong");
    delete[] seen_;
    seen_size_ = size_x * size_y;
    //这里分配了一个size和master map一样的bool数组
    seen_ = new bool[seen_size_];
  }
  memset(seen_, false, size_x * size_y * sizeof(bool));
  
  // We need to include in the inflation cells outside the bounding
  // box min_i...max_j, by the amount cell_inflation_radius_.  Cells
  // up to that distance outside the box can still influence the costs
  // stored in cells inside the box.
  //边际膨胀
  min_i -= cell_inflation_radius_;
  min_j -= cell_inflation_radius_;
  max_i += cell_inflation_radius_;
  max_j += cell_inflation_radius_;

  min_i = std::max(0, min_i);
  min_j = std::max(0, min_j);
  max_i = std::min(int(size_x), max_i);
  max_j = std::min(int(size_y), max_j);

接下来遍历bound中的cell,找到cost为LETHAL_OBSTACLE,即障碍物cell,将其以CellData形式放进inflation_cells_[0.0]中,inflation_cells_的定义如下:

std::map<double, std::vector > inflation_cells_;

它是一个映射,由浮点数→CellData数组,CellData这个类定义在inflation_layer.h中,是专门用来记录当前cell的索引和与它最近的障碍物的索引的。这个映射以距离障碍物的距离为标准给bound内的cell归类,为膨胀做准备;

自然距离为0对应的cell即障碍物cell本身,目前得到的inflation_cells_只包括障碍物本身。

  std::vector<CellData>& obs_bin = inflation_cells_[0.0];
  for (int j = min_j; j < max_j; j++)
  {
    for (int i = min_i; i < max_i; i++)
    {
      int index = master_grid.getIndex(i, j);
      unsigned char cost = master_array[index];
      if (cost == LETHAL_OBSTACLE)
      {
        obs_bin.push_back(CellData(index, i, j, i, j));
      }
    }
  }

接下来开始由目前的inflation_cells_进行传播,直到将所有的cell填充进去。

二重循环,外层遍历“键”,即距障碍物的距离;内层遍历“值”,即cell。

内部循环记录当前cell的坐标和离它最近的cell的坐标,然后调用costLookup函数,它会用到我们的参考矩阵cached_costs_,通过该cell与最近障碍物的距离来确定该cell的cost,这里称为新cost。

当原cost为NO_INFORMATION:

  • inflate_unknown_为true:当新cost>0,设为新cost;
  • inflate_unknown_为false:新cost≥INSCRIBED_INFLATED_OBSTACLE,设为新cost

区别就在于,如果inflate unknown,则当膨胀到主地图上的未知区域,只要有cost,就覆盖它;而当inflate unknown关闭,当膨胀到主地图上的未知区域时,只有新cost是障碍物,才覆盖它,否则维持未知。后者膨胀的范围更窄!

否则,取二者中大的cost

接下来enqueue函数会将其四周的cell按照距离远近加入inflation_cells_对应的键下,内容后述。

至此完成一个轮次的循环,接下来不断循环(不更新已经seen_的cell),完成传播。(与全局规划中potarr的传播类似)

  // Process cells by increasing distance; new cells are appended to the corresponding distance bin, so they
  // can overtake previously inserted but farther away cells
  //处理cells,增加距离
  std::map<double, std::vector<CellData> >::iterator bin;
  for (bin = inflation_cells_.begin(); bin != inflation_cells_.end(); ++bin)
  {
    //map键值对映射,键是距离最近的障碍物的距离,值是cell
    //second是“键”“值”对中的“值”,即遍历次数为celldata的个数
    for (int i = 0; i < bin->second.size(); ++i)
    {
      // process all cells at distance dist_bin.first
      //在该“double键”下记录迭代到的celldata
      const CellData& cell = bin->second[i];
      //记录该celldata的索引index
      unsigned int index = cell.index_;

      //如果已经访问过,跳过
      if (seen_[index])
      {
        continue;
      }
      //标记
      seen_[index] = true;
      //得到该cell的坐标和离它最近的障碍物的坐标
      unsigned int mx = cell.x_;
      unsigned int my = cell.y_;
      unsigned int sx = cell.src_x_;
      unsigned int sy = cell.src_y_;

      //根据该CELL与障碍的距离来分配cost
      unsigned char cost = costLookup(mx, my, sx, sy);//输入该cell坐标和离它最近的障碍物坐标,返回对应的cached_costs_(cached_costs_数组怎么定义的?)
      unsigned char old_cost = master_array[index];//旧celcost,是master地图上的cost
      if (old_cost == NO_INFORMATION && (inflate_unknown_ ? (cost > FREE_SPACE) : (cost >= INSCRIBED_INFLATED_OBSTACLE)))
        master_array[index] = cost;//通过比较,更新主地图cost
      else
        master_array[index] = std::max(old_cost, cost);

      // attempt to put the neighbors of the current cell onto the inflation list
      //把当前cell的四周的点也放进inflation list
      if (mx > 0)
        enqueue(index - 1, mx - 1, my, sx, sy);
      if (my > 0)
        enqueue(index - size_x, mx, my - 1, sx, sy);
      if (mx < size_x - 1)
        enqueue(index + 1, mx + 1, my, sx, sy);
      if (my < size_y - 1)
        enqueue(index + size_x, mx, my + 1, sx, sy);
    }
  }

  inflation_cells_.clear();
}

<5> “传播” InflationLayer::enquene

这个函数通过调用distanceLookup函数,在我们的参考矩阵cached_distances_上,找到当前cell与最近的障碍物cell的距离,当距离在阈值内,将当前cell加入到inflation_cells_相应键(表示距离)下。

inline void InflationLayer::enqueue(unsigned int index, unsigned int mx, unsigned int my,
                                    unsigned int src_x, unsigned int src_y)
{
  if (!seen_[index])
  {
    // we compute our distance table one cell further than the inflation radius dictates so we can make the check below
    double distance = distanceLookup(mx, my, src_x, src_y);
    //找它和最近的障碍物的距离,如果超过了阈值,则直接返回
    //如果不超过阈值,就把它也加入inflation_cells_数组里
    // we only want to put the cell in the list if it is within the inflation radius of the obstacle point
    if (distance > cell_inflation_radius_)
      return;

    // push the cell data onto the inflation list and mark
    inflation_cells_[distance].push_back(CellData(index, mx, my, src_x, src_y));
  }
}





Neo 2020.3

评论 7
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值