Apollo6.0 StBoundsDecider流程与代码解析

Apollo6.0 StBoundsDecider流程与代码解析

前言

对于纵向决策与规划而言,需要依据障碍物的预测轨迹、类型等,构建其st_boundary映射至planned_path上,并对其进行决策打标签(yield, overtake…);轨迹规划模块再依据决策信息,添加对应求解目标、约束条件,求解处”最优”轨迹。

本文主要对StBoundsDecider进行解析,StBoundsDecider模块内容较多,之前花了不少时间解析。

文中如有错误之处,恳请各位大佬指正!

一、流程与代码解析

STBoundsDecider 主要是对动态以及最近的一个静态且阻塞当前引导路径的障碍物进行st图构建,对不影响纵向规划的障碍物设置IGNORE属性,并按照设定轨迹给出每一个障碍物boundary的最优决策(overtake/yield),最终决策出最优的Drivable_st_boundary;
算法主流程见 STBoundsDecider::Process()
主要包含内容可见下图:

Apollo6.0 StBoundsDecider流程与代码解析
  1. InitSTBoundsDecider()函数

  2. 初始化 st_obstacles_process_;

  3. 基于优化求解后的横向路径path_data,构建障 碍物映射至该路径上的st图,见 STObstaclesProcessor::MapObstaclesToSTBoundary函数:
  4. 记录低路权的路段(OUT_ON_FORWARD_LANE/OUT_ON_REVERSE_LANE)
  5. 遍历障碍物:
    • ComputeObstacleSTBoundary(),计算障碍物的st_boundary;对于静态障碍物,标记为is_caution_obstacle;动态障碍物,则与低路权路权进行位置匹配,确定其obs_caution_end_t时间;
Status STObstaclesProcessor::MapObstaclesToSTBoundaries(
    PathDecision* const path_decision) {
  // Sanity checks.

  ...

  ...

  // 更新低路权区域
  bool is_adc_low_road_right_beginning = true;
  for (const auto& path_pt_info : path_data_.path_point_decision_guide()) {
    double path_pt_s = 0.0;
    PathData::PathPointType path_pt_type;
    std::tie(path_pt_s, path_pt_type, std::ignore) = path_pt_info;
    if (path_pt_type == PathData::PathPointType::OUT_ON_FORWARD_LANE ||
        path_pt_type == PathData::PathPointType::OUT_ON_REVERSE_LANE) {
      if (is_adc_low_road_right_beginning) {
        adc_low_road_right_segments_.emplace_back(path_pt_s, path_pt_s);
        is_adc_low_road_right_beginning = false;
      } else {
        adc_low_road_right_segments_.back().second = path_pt_s;
      }
    } else if (path_pt_type == PathData::PathPointType::IN_LANE) {
      if (!is_adc_low_road_right_beginning) {
        is_adc_low_road_right_beginning = true;
      }
    }
  }

  std::unordered_set<std::string> non_ignore_obstacles;
  std::tuple<std::string, stboundary, obstacle*> closest_stop_obstacle;
  std::get<0>(closest_stop_obstacle) = "NULL";
  //&#x904D;&#x5386;&#x6BCF;&#x4E00;&#x4E2A;&#x969C;&#x788D;&#x7269;&#xFF0C;&#x8BA1;&#x7B97;&#x5176;st_boundary&#xFF1B;&#x6CE8;&#x610F;&#xFF0C;&#x8BE5;&#x6A21;&#x5757;&#x8BA1;&#x7B97;&#x51FA;&#x7684;lower_points&#x548C;upper_points&#x5206;&#x8FA8;&#x7387;&#x8F83;&#x7C97;&#xFF0C;&#x78B0;&#x649E;&#x6821;&#x9A8C;&#x4E0D;&#x7CBE;&#x786E;
  for (const auto* obs_item_ptr : path_decision->obstacles().Items()) {
    // Sanity checks.

    Obstacle* obs_ptr = path_decision->Find(obs_item_ptr->Id());
    if (obs_ptr == nullptr) {
      const std::string msg = "Null obstacle pointer.";
      AERROR << msg;
      return Status(ErrorCode::PLANNING_ERROR, msg);
    }

    // Draw the obstacle's st-boundary.

    std::vector<stpoint> lower_points;
    std::vector<stpoint> upper_points;
    bool is_caution_obstacle = false;
    double obs_caution_end_t = 0.0;
    //&#x4F9D;&#x636E;&#x4F18;&#x5316;&#x540E;&#x7684;&#x8DEF;&#x5F84;&#x8BA1;&#x7B97;&#x969C;&#x788D;&#x7269;&#x7684;&#x4E0A;&#x4E0B;&#x754C;&#xFF0C;&#x8BA1;&#x7B97;&#x51FA;&#x7684;&#x8FB9;&#x754C;&#x7C92;&#x5EA6;&#x8F83;&#x7C97;&#x3002;
    if (!ComputeObstacleSTBoundary(*obs_ptr, &lower_points, &upper_points,
                                   &is_caution_obstacle, &obs_caution_end_t)) {
      continue;
    }
  &#x3000;//&#x5BF9;&#x4E0A;&#x4E0B;&#x8FB9;&#x754C;&#x70B9;&#x4E0D;&#x505A;&#x5220;&#x51CF;&#xFF0C;&#x4FDD;&#x7559;&#x539F;&#x59CB;&#x6570;&#x503C;
    auto boundary =
        STBoundary::CreateInstanceAccurate(lower_points, upper_points);
    boundary.set_id(obs_ptr->Id());
    if (is_caution_obstacle) {
      boundary.set_obstacle_road_right_ending_t(obs_caution_end_t);
    }
    // &#x5C06;&#x5904;&#x4E8E;&#x975E;&#x4F4E;&#x8DEF;&#x6743;&#x533A;&#x57DF;&#x7684;&#x4E0A;&#x4E0B;&#x8FB9;&#x754C;&#x5220;&#x6389;
    while (lower_points.size() > 2 &&
           lower_points.back().t() > obs_caution_end_t) {
      lower_points.pop_back();
    }
    while (upper_points.size() > 2 &&
           upper_points.back().t() > obs_caution_end_t) {
      upper_points.pop_back();
    }
    auto alternative_boundary =
        STBoundary::CreateInstanceAccurate(lower_points, upper_points);
    alternative_boundary.set_id(obs_ptr->Id());
    obs_id_to_alternative_st_boundary_[obs_ptr->Id()] = alternative_boundary;

    // Store all Keep-Clear zone together.

    if (obs_item_ptr->Id().find("KC") != std::string::npos) {
      candidate_clear_zones_.push_back(
          make_tuple(obs_ptr->Id(), boundary, obs_ptr));
      continue;
    }

    //&#x627E;&#x5230;&#x8DDD;&#x79BB;&#x6700;&#x8FD1;&#x7684;&#x4E00;&#x4E2A;static&#x969C;&#x788D;&#x7269;&#xFF0C;&#x5C06;&#x5176;&#x5B58;&#x81F3;closest_stop_obstacle;
    //&#x5FFD;&#x7565;&#x81EA;&#x8F66;&#x8EAB;&#x540E;&#x7684;&#x52A8;&#x6001;&#x969C;&#x788D;&#x7269;
    if (obs_ptr->Trajectory().trajectory_point().empty()) {
      // Obstacle is static.

      if (std::get<0>(closest_stop_obstacle) == "NULL" ||
          std::get<1>(closest_stop_obstacle).bottom_left_point().s() >
              boundary.bottom_left_point().s()) {
        // If this static obstacle is closer for ADC to stop, record it.

        closest_stop_obstacle =
            std::make_tuple(obs_ptr->Id(), boundary, obs_ptr);
      }
    } else {
      // Obstacle is dynamic.

      if (boundary.bottom_left_point().s() - adc_path_init_s_ <
              kSIgnoreThreshold &&
          boundary.bottom_left_point().t() > kTIgnoreThreshold) {
        continue;
      }
      obs_id_to_st_boundary_[obs_ptr->Id()] = boundary;
      obs_ptr->set_path_st_boundary(boundary);
      non_ignore_obstacles.insert(obs_ptr->Id());
      ADEBUG << "Adding " << obs_ptr->Id() << " into the ST-graph.";
    }
  }

  //&#x5B58;&#x50A8;&#x6700;&#x8FD1;&#x7684;static&#x969C;&#x788D;&#x7269;boundary&#x5230;obs_id_boundary map&#x5BB9;&#x5668;&#x4E2D;
  //&#x5982;&#x679C;static&#x969C;&#x788D;&#x7269;&#x8FB9;&#x754C;&#x4E0E;keepclear&#x533A;&#x57DF;&#x53D1;&#x751F;&#x91CD;&#x53E0;&#xFF0C;&#x5219;&#x66F4;&#x65B0;&#x5BF9;&#x5E94;&#x7684;id/boundary/obs_ptr
  if (std::get<0>(closest_stop_obstacle) != "NULL") {
    std::string closest_stop_obs_id;
    STBoundary closest_stop_obs_boundary;
    Obstacle* closest_stop_obs_ptr;
    std::tie(closest_stop_obs_id, closest_stop_obs_boundary,
             closest_stop_obs_ptr) = closest_stop_obstacle;

    // Go through all Keep-Clear zones, and see if there is an even closer
    // stop fence due to them.

    if (!closest_stop_obs_ptr->IsVirtual()) {
      for (const auto& clear_zone : candidate_clear_zones_) {
        const auto& clear_zone_boundary = std::get<1>(clear_zone);
        if (closest_stop_obs_boundary.min_s() >= clear_zone_boundary.min_s() &&
            closest_stop_obs_boundary.min_s() <= clear_zone_boundary.max_s()) { std::tie(closest_stop_obs_id, closest_stop_obs_boundary, closest_stop_obs_ptr)="clear_zone;" adebug << "clear zone " closest_stop_obs_id is closer."; break; } obs_id_to_st_boundary_[closest_stop_obs_id]="closest_stop_obs_boundary;" closest_stop_obs_ptr->set_path_st_boundary(closest_stop_obs_boundary);
    non_ignore_obstacles.insert(closest_stop_obs_id);
    ADEBUG << "Adding " << closest_stop_obs_ptr->Id() << " into the ST-graph.";
    ADEBUG << "min_s = " << closest_stop_obs_boundary.min_s();
  }

  // &#x5C06;&#x672A;&#x6DFB;&#x52A0;&#x8FDB;non_ignore_obstacles&#x5BB9;&#x5668;&#x4E2D;&#x7684;&#x969C;&#x788D;&#x7269;&#x6A2A;&#x7EB5;&#x5411;Decision&#x4E3A;IGNORE
  for (const auto* obs_item_ptr : path_decision->obstacles().Items()) {
    Obstacle* obs_ptr = path_decision->Find(obs_item_ptr->Id());
    if (non_ignore_obstacles.count(obs_ptr->Id()) == 0) {
      ObjectDecisionType ignore_decision;
      ignore_decision.mutable_ignore();
      if (!obs_ptr->HasLongitudinalDecision()) {
        obs_ptr->AddLongitudinalDecision("st_obstacle_processor",
                                         ignore_decision);
      }
      if (!obs_ptr->HasLateralDecision()) {
        obs_ptr->AddLateralDecision("st_obstacle_processor", ignore_decision);
      }
    }
  }

  // Preprocess the obstacles for sweep-line algorithms.

  // Fetch every obstacle's beginning end ending t-edges only.

  //&#x6BCF;&#x4E2A;&#x969C;&#x788D;&#x7269;&#x53EA;&#x9700;&#x8981;&#x5B58;&#x50A8;&#x5176;&#x9996;&#x5C3E;t/&#x4E0A;&#x4E0B;&#x754C;s/id&#x4FE1;&#x606F;
  for (const auto& it : obs_id_to_st_boundary_) {
    obs_t_edges_.emplace_back(true, it.second.min_t(),
                              it.second.bottom_left_point().s(),
                              it.second.upper_left_point().s(), it.first);
    obs_t_edges_.emplace_back(false, it.second.max_t(),
                              it.second.bottom_right_point().s(),
                              it.second.upper_right_point().s(), it.first);
  }
  // Sort the edges.

  //&#x5148;&#x6309;&#x8D77;&#x59CB;start_s&#x4F4D;&#x7F6E;&#x5347;&#x5E8F;&#x6392;&#x5E8F;&#xFF0C;&#x82E5;&#x76F8;&#x540C;&#xFF0C;&#x5219;&#x6309;&#x662F;&#x5426;&#x4E3A;start&#x964D;&#x5E8F;&#x6392;&#x5E8F;
  std::sort(obs_t_edges_.begin(), obs_t_edges_.end(),
            [](const ObsTEdge& lhs, const ObsTEdge& rhs) {
              if (std::get<1>(lhs) != std::get<1>(rhs)) {
                return std::get<1>(lhs) < std::get<1>(rhs);
              } else {
                return std::get<0>(lhs) > std::get<0>(rhs);
              }
            });

  return Status::OK();
}
</0></0></1></1></1></1></=></1></0></1></0></stpoint></stpoint></0></std::string,></std::string>
&#x5229;&#x7528;&#x5411;&#x91CF;&#x70B9;&#x4E58;&#x3001;&#x53C9;&#x4E58;&#x8BA1;&#x7B97;&#x969C;&#x788D;&#x7269;&#x4E0E;&#x89C4;&#x5212;&#x8DEF;&#x5F84;&#x4E0A;&#x81EA;&#x8F66;&#x78B0;&#x649E;&#x65F6;&#x523B;&#x7684;&#x6700;&#x8FD1;&#x4F4D;&#x7F6E;
bool STObstaclesProcessor::IsPathPointAwayFromObstacle(
    const PathPoint& path_point, const PathPoint& direction_point,
    const Box2d& obs_box, const double s_thresh, const bool is_before) {
  Vec2d path_pt(path_point.x(), path_point.y());
  Vec2d dir_pt(direction_point.x(), direction_point.y());
  LineSegment2d path_dir_lineseg(path_pt, dir_pt);
  LineSegment2d normal_line_seg(path_pt, path_dir_lineseg.rotate(M_PI_2));

  auto corner_points = obs_box.GetAllCorners();
  for (const auto& corner_pt : corner_points) {
    Vec2d normal_line_ft_pt;
    normal_line_seg.GetPerpendicularFoot(corner_pt, &normal_line_ft_pt);
    Vec2d path_dir_unit_vec = path_dir_lineseg.unit_direction();
    Vec2d perpendicular_vec = corner_pt - normal_line_ft_pt;
    double corner_pt_s_dist = path_dir_unit_vec.InnerProd(perpendicular_vec);
    if (is_before && corner_pt_s_dist < s_thresh) {
      return false;
    }
    if (!is_before && corner_pt_s_dist > -s_thresh) {
      return false;
    }
  }
  return true;
}

示意图如下:

Apollo6.0 StBoundsDecider流程与代码解析
  • 初始化启发式st曲线 st_guide_line和自车运动学约束边界 st_driving_limits_;
  //&#x6B64;&#x5904;desire_speed&#x5E94;&#x8BE5;&#x7ED3;&#x5408;&#x81EA;&#x8F66;set_speed&#x4EE5;&#x53CA;tfl speed_limit&#x7EA6;&#x675F;
  static constexpr double desired_speed = 15.0;
  // If the path_data optimization is guided from a reference path of a
  // reference trajectory, use its reference speed profile to select the st
  // bounds in LaneFollow Hybrid Mode
  if (path_data.is_optimized_towards_trajectory_reference()) {
    st_guide_line_.Init(desired_speed,
                        injector_->learning_based_data()
                            ->learning_data_adc_future_trajectory_points());
  } else {
    st_guide_line_.Init(desired_speed);
  }
  static constexpr double max_acc = 2.5;
  static constexpr double max_dec = 5.0;
  static constexpr double max_v = desired_speed * 1.5;
  st_driving_limits_.Init(max_acc, max_dec, max_v,
                          frame.PlanningStartPoint().v());
  1. GenerateRegularSTBound:生成常规可通行st_bound和vt_bound边界,遍历st_bound:

  2. 依据运动学driving_limits更新s_lower, s_upper;

  3. 依据障碍物st_boundary约束,更新可通行s_bounds以及对应的决策(GetBoundsFromDecisions),对于同一障碍物的st_boundary可能存在多个决策,比如overtake或yield,见 GetSBoundsFromDecisions函数;
bool STObstaclesProcessor::GetSBoundsFromDecisions(
    double t, std::vector<std::pair<double, double>>* const available_s_bounds,
    std::vector<std::vector<std::pair<std::string, objectdecisiontype>>>* const
        available_obs_decisions) {
    ...

  while (obs_t_edges_idx_ < static_cast<int>(obs_t_edges_.size()) &&
         std::get<1>(obs_t_edges_[obs_t_edges_idx_]) <= t) { if (std::get<0>(obs_t_edges_[obs_t_edges_idx_]) == 0 &&
        std::get<1>(obs_t_edges_[obs_t_edges_idx_]) == t) {
      break;
    }
    ...

    //&#x53EA;&#x6709;&#x5F53;&#x969C;&#x788D;&#x7269;&#x521A;&#x8FDB;&#x5165;&#xFF0C;&#x6216;&#x8005;&#x5F53;&#x524D;t&#x5927;&#x4E8E;&#x969C;&#x788D;&#x7269;&#x7684;end_t&#xFF0C;&#x624D;&#x4F1A;push&#x8FDB;&#x6765;
    new_t_edges.push_back(obs_t_edges_[obs_t_edges_idx_]);
    ++obs_t_edges_idx_;
  }
  //&#x5982;&#x679C;&#x969C;&#x788D;&#x7269;is_starting &#x6807;&#x5FD7;&#x4E3A;false,&#x5219;&#x9700;&#x8981;&#x5C06;&#x5176;&#x5220;&#x9664;
  for (const auto& obs_t_edge : new_t_edges) {
    if (std::get<0>(obs_t_edge) == 0) {
      ADEBUG << "Obstacle id: " << std::get<4>(obs_t_edge)
             << " is leaving st-graph.";
      if (obs_id_to_decision_.count(std::get<4>(obs_t_edge)) != 0) {
        obs_id_to_decision_.erase(std::get<4>(obs_t_edge));
      }
    }
  }
  //&#x5BF9;&#x4E8E;&#x5DF2;&#x7ECF;&#x8D85;&#x8FC7;&#x7684;&#x969C;&#x788D;&#x7269;,&#x9700;&#x8981;&#x5728;&#x8D85;&#x8FC7;&#x5176;end_t(&#x52A0;&#x9608;&#x503C;&#x65F6;&#x95F4;)&#x540E;&#x5C06;&#x5176;&#x4ECE;&#x5B58;&#x50A8;&#x5BB9;&#x5668;&#x4E2D;&#x5220;&#x6389;
  std::vector<std::string> obs_id_to_remove;
  for (const auto& obs_id_to_decision_pair : obs_id_to_decision_) {...}
  for (const auto& obs_id : obs_id_to_remove) {
    obs_id_to_decision_.erase(obs_id);
    ...

  }

  //&#x4F9D;&#x636E;&#x969C;&#x788D;&#x7269;obs_id_decision&#x4FE1;&#x606F;&#xFF0C;&#x4ECE;&#x5176;st_boundary&#x8BA1;&#x7B97;&#x5904;s_min/s_max&#x8FB9;&#x754C;&#xFF0C;&#x6BD4;&#x5982;&#x8FD9;&#x4E2A;&#x969C;&#x788D;&#x7269;obs_decision == overtake,&#x5219;s_min >= obs_s_max(t&#x65F6;&#x523B;&#x969C;&#x788D;&#x7269;boundary&#x4E0A;&#x8FB9;&#x754C;)
  double s_min = 0.0;
  double s_max = planning_distance_;
  for (auto it : obs_id_to_decision_) {
  ...

  }

//&#x5BF9;&#x65B0;&#x8FDB;&#x5165;&#x7684;&#x969C;&#x788D;&#x7269;&#x4FE1;&#x606F;&#xFF0C;&#x8FDB;&#x884C;&#x4F4D;&#x7F6E;&#x4E0A;&#x5224;&#x65AD;&#xFF0C;&#x505A;&#x51FA;&#x660E;&#x786E;&#x6216;&#x8005;&#x6A21;&#x7CCA;&#x7684;&#x51B3;&#x7B56;
  std::vector<obstedge> ambiguous_t_edges;
  for (auto obs_t_edge : new_t_edges) {
    if (std::get<0>(obs_t_edge) == 1) {
      //&#x969C;&#x788D;&#x7269;&#x7684;&#x4E0B;&#x8FB9;&#x754C;>= s_max&#xFF0C;&#x5219;&#x5224;&#x65AD;yield&#x3000;action
      if (std::get<2>(obs_t_edge) >= s_max) {
        ADEBUG << "  Apparently, it should be yielded.";
        obs_id_to_decision_[std::get<4>(obs_t_edge)] =
            DetermineObstacleDecision(std::get<2>(obs_t_edge),
                                      std::get<3>(obs_t_edge), s_max);
        obs_id_to_st_boundary_[std::get<4>(obs_t_edge)].SetBoundaryType(
            STBoundary::BoundaryType::YIELD);
      } else if (std::get<3>(obs_t_edge) <= s_min) { adebug << " apparently, it should be overtaken."; obs_id_to_decision_[std::get<4>(obs_t_edge)] =
            DetermineObstacleDecision(std::get<2>(obs_t_edge),
                                      std::get<3>(obs_t_edge), s_min);
        obs_id_to_st_boundary_[std::get<4>(obs_t_edge)].SetBoundaryType(
            STBoundary::BoundaryType::OVERTAKE);
      } else {
        ADEBUG << "  It should be further analyzed.";
        ambiguous_t_edges.push_back(obs_t_edge);
      }
    }
  }
//&#x5BF9;&#x4E8E;&#x51B3;&#x7B56;&#x6A21;&#x7CCA;&#x7684;&#x60C5;&#x51B5;&#xFF0C;&#x5148;&#x53BB;&#x5BFB;&#x627E;&#x5BF9;&#x5E94;&#x7684;&#x53EF;&#x901A;&#x884C;&#x4E0A;&#x4E0B;&#x8FB9;&#x754C;
//FindSGaps&#x5185;&#x90E8;&#x6392;&#x5E8F;&#x65B9;&#x6CD5;&#xFF1A;&#x5148;&#x6309;s&#x5927;&#x5C0F;&#x6392;&#x5E8F;&#xFF1B;&#x518D;&#x8005;&#x6309;&#x662F;&#x5426;&#x4E3A;staring_flag&#x6765;&#x6392;&#x5E8F;
  auto s_gaps = FindSGaps(ambiguous_t_edges, s_min, s_max);

//&#x4F9D;&#x636E;&#x53EF;&#x901A;&#x884C;&#x7A7A;&#x95F4;sgap,&#x904D;&#x5386;&#xFF0C;&#x5E76;&#x6620;&#x5C04;&#x81F3;&#x5BF9;&#x5E94;&#x7684;&#x969C;&#x788D;&#x7269;&#x4E0A;&#xFF0C;&#x5BF9;&#x6BCF;&#x4E2A;&#x5177;&#x6709;st map&#x5C5E;&#x6027;&#x7684;&#x969C;&#x788D;&#x7269;&#x8FDB;&#x884C;&#x6253;&#x6807;&#x7B7E;&#x3002;
  for (auto s_gap : s_gaps) {
    available_s_bounds->push_back(s_gap);
    std::vector<std::pair<std::string, objectdecisiontype>> obs_decisions;
    for (auto obs_t_edge : ambiguous_t_edges) {
      std::string obs_id = std::get<4>(obs_t_edge);
      double obs_s_min = std::get<2>(obs_t_edge);
      double obs_s_max = std::get<3>(obs_t_edge);
      obs_decisions.emplace_back(
          obs_id,
          DetermineObstacleDecision(obs_s_min, obs_s_max,
                                    (s_gap.first + s_gap.second) / 2.0));//&#x51B3;&#x7B56;&#x5BF9;&#x8BE5;&#x969C;&#x788D;&#x7269;&#x662F;overtake&#x8FD8;&#x662F;yield
    }
    available_obs_decisions->push_back(obs_decisions);
  }
}
</3></2></4></std::pair<std::string,></4></3></2></=></3></4></3></2></4></2></0></obstedge></std::string></4></4></4></0></1></=></1></int></std::vector<std::pair<std::string,></std::pair<double,>

Apollo6.0 StBoundsDecider流程与代码解析
  • 依据自车运动学约束,剔除不可达的障碍物decision,见 RemoveInvalidDecisions函数;
void STBoundsDecider::RemoveInvalidDecisions(
    std::pair<double, double> driving_limit,
    std::vector<std::pair<stboundpoint, obsdecset>>* available_choices) {
  // Remove those choices that don't even fall within driving-limits.

  size_t i = 0;
  while (i < available_choices->size()) {
    double s_lower = 0.0;
    double s_upper = 0.0;
    std::tie(std::ignore, s_lower, s_upper) = available_choices->at(i).first;
    if (s_lower > driving_limit.second || s_upper < driving_limit.first) {
      //&#x8D85;&#x51FA;&#x8FD0;&#x52A8;&#x5B66;&#x7EA6;&#x675F;&#x7684;decision choice,&#x5C06;&#x5176;&#x79FB;&#x81F3;&#x672B;&#x5C3E;pop&#x6389;
      // Invalid bound, should be removed.

      if (i != available_choices->size() - 1) {
        swap(available_choices->at(i),
             available_choices->at(available_choices->size() - 1));
      }
      available_choices->pop_back();
    } else {
      // Valid bound, proceed to the next one.

      ++i;
    }
  }
}
</std::pair<stboundpoint,></double,>
  • 接下来是对avaliable_choices进行按规则迭代排序,直至容器内元素变得有序退出。比如对于obs2,有着overtake 和yield两种决策。按照可通行区间大小优先,其次可通行空间包含guide_line优先。
void STBoundsDecider::RankDecisions(
    double s_guide_line, std::pair<double, double> driving_limit,
    std::vector<std::pair<stboundpoint, obsdecset>>* available_choices) {
  // Perform sorting of the existing decisions.

  bool has_swaps = true;
  while (has_swaps) {
    has_swaps = false;
    for (int i = 0; i < static_cast<int>(available_choices->size()) - 1; ++i) {
      ...

      // &#x53EA;&#x8981;&#x4E24;&#x4E2A;&#x53EF;&#x901A;&#x884C;&#x7A7A;&#x95F4;&#x4E2D;&#x6709;&#x4E00;&#x4E2A;&#x901A;&#x884C;&#x533A;&#x95F4;&#x5C0F;&#x4E8E;&#x9608;&#x503C;&#xFF0C;&#x9009;&#x5176;&#x4E2D;&#x8F83;&#x5927;&#x7A7A;&#x95F4;&#x7684;&#x901A;&#x884C;&#x533A;&#x57DF;
      double A_room = std::fmin(driving_limit.second, A_s_upper) -
                      std::fmax(driving_limit.first, A_s_lower);
      double B_room = std::fmin(driving_limit.second, B_s_upper) -
                      std::fmax(driving_limit.first, B_s_lower);
      if (A_room < kSTPassableThreshold || B_room < kSTPassableThreshold) {
        if (A_room < B_room) {
          swap(available_choices->at(i + 1), available_choices->at(i));
          has_swaps = true;
          ADEBUG << "Swapping to favor larger room.";
        }
        continue;
      }

      // &#x4F18;&#x5148;&#x9009;&#x62E9;&#x4E0E;s_guide_line&#x6709;&#x91CD;&#x53E0;&#x7684;&#x901A;&#x884C;&#x533A;&#x57DF;
      bool A_contains_guideline =
          A_s_upper >= s_guide_line && A_s_lower <= s_guide_line; bool b_contains_guideline="B_s_upper">= s_guide_line && B_s_lower <= s_guide_line; if (a_contains_guideline !="B_contains_guideline)" { (!a_contains_guideline) swap(available_choices->at(i + 1), available_choices->at(i));
          has_swaps = true;
        }
        continue;
      }
    }
  }
}
</=></=></int></std::pair<stboundpoint,></double,>

下图,B_room与s_guide_line有重叠,优先选择B_room;

Apollo6.0 StBoundsDecider流程与代码解析
  • 找到优先级最高的可通行空间并赋值给obstacleDecision()
auto top_choice_decision = available_choices.front().second;
st_obstacles_processor_.SetObstacleDecision(top_choice_decision);
  • 更新s_guide_line/st_driving_limits/v_limts
// Update st-guide-line, st-driving-limit info, and v-limits,&#x4E3B;&#x8981;&#x662F;st/sv&#x4E0A;&#x4E0B;&#x8FB9;&#x754C;.

std::pair<double, double> limiting_speed_info;
if (st_obstacles_processor_.GetLimitingSpeedInfo(t, &limiting_speed_info)) {
  st_driving_limits_.UpdateBlockingInfo(t, s_lower, limiting_speed_info.first, s_upper,
          limiting_speed_info.second);
  st_guide_line_.UpdateBlockingInfo(t, s_lower, true);
  st_guide_line_.UpdateBlockingInfo(t, s_upper, false);
  if (is_limited_by_lower_obs) {
    lower_obs_v = limiting_speed_info.first;
  }
  if (is_limited_by_upper_obs) {
    upper_obs_v = limiting_speed_info.second;
  }
}

st_bound->at(i) = std::make_tuple(t, s_lower, s_upper);
vt_bound->at(i) = std::make_tuple(t, lower_obs_v, upper_obs_v);
</double,>
  1. 将可通行区域st_bound,vt_bound赋值给reference_line_info中的STDrivableBoundary()
    st_graph_data->SetSTDrivableBoundary(regular_st_bound, regular_vt_bound);

二、总结

StBoundsDecider模块内容很多,个人觉得该模块主要的工作就是:

  • 生成DrivableSTBoundary;
  • 对不影响纵向规划的障碍物设置IGNORE属性;

本模块障碍物的ST图计算耗时也较高,但st_boundary精度较低;同理最终生成的st_drivable_boundary_边界精度也较低。如果在下游gridded_path_time_graph模块中FLAGS_use_st_drivable_boundary不置位时,则无需使用该模块输出的st_drivable_boundary;因此可结合实际项目需求,来精简该模块的冗余计算。

三、参考

在此,感谢本文中索引的博客大佬们将知识share,感谢Baidu apollo开源算法!。

Original: https://blog.csdn.net/xl_courage/article/details/121652943
Author: xl_courage
Title: Apollo6.0 StBoundsDecider流程与代码解析

原创文章受到原创版权保护。转载请注明出处:https://www.johngo689.com/597836/

转载文章受原作者版权保护。转载请注明原作者出处!

(0)

大家都在看

亲爱的 Coder【最近整理,可免费获取】👉 最新必读书单  | 👏 面试题下载  | 🌎 免费的AI知识星球