【Apollo学习笔记】——规划模块TASK之PATH_BOUNDS_DECIDER

news2025/1/23 22:40:58

文章目录

  • 前言
  • PATH_BOUNDS_DECIDER功能简介
  • PATH_BOUNDS_DECIDER相关配置
  • PATH_BOUNDS_DECIDER总体流程
    • InitPathBoundsDecider
    • 1. fallback
      • GenerateFallbackPathBound
        • InitPathBoundary
        • GetBoundaryFromLanesAndADC
          • UpdatePathBoundaryWithBuffer
          • TrimPathBounds
    • 2. pull over
      • GeneratePullOverPathBound
        • GetBoundaryFromRoads
        • UpdatePullOverBoundaryByLaneBoundary
        • GetBoundaryFromStaticObstacles
        • SearchPullOverPosition
    • 3. lane change
      • GenerateLaneChangePathBound
        • GetBoundaryFromLaneChangeForbiddenZone
    • 4. regular

前言

在Apollo星火计划学习笔记——Apollo路径规划算法原理与实践与【Apollo学习笔记】——Planning模块讲到……Stage::Process的PlanOnReferenceLine函数会依次调用task_list中的TASK,本文将会继续以LaneFollow为例依次介绍其中的TASK部分究竟做了哪些工作。由于个人能力所限,文章可能有纰漏的地方,还请批评斧正。

modules/planning/conf/scenario/lane_follow_config.pb.txt配置文件中,我们可以看到LaneFollow所需要执行的所有task。

stage_config: {
  stage_type: LANE_FOLLOW_DEFAULT_STAGE
  enabled: true
  task_type: LANE_CHANGE_DECIDER
  task_type: PATH_REUSE_DECIDER
  task_type: PATH_LANE_BORROW_DECIDER
  task_type: PATH_BOUNDS_DECIDER
  task_type: PIECEWISE_JERK_PATH_OPTIMIZER
  task_type: PATH_ASSESSMENT_DECIDER
  task_type: PATH_DECIDER
  task_type: RULE_BASED_STOP_DECIDER
  task_type: SPEED_BOUNDS_PRIORI_DECIDER
  task_type: SPEED_HEURISTIC_OPTIMIZER
  task_type: SPEED_DECIDER
  task_type: SPEED_BOUNDS_FINAL_DECIDER
  task_type: PIECEWISE_JERK_SPEED_OPTIMIZER
  # task_type: PIECEWISE_JERK_NONLINEAR_SPEED_OPTIMIZER
  task_type: RSS_DECIDER

本文将继续介绍LaneFollow的第四个TASK——PATH_BOUNDS_DECIDER

PATH_BOUNDS_DECIDER功能简介

在这里插入图片描述利用前几个决策器,根据相应条件,产生相应的SL边界。这里说明以下Nudge障碍物的概念——主车旁边的障碍物未完全阻挡主车,主车可以通过绕行避过障碍物(注意图中的边界)。

PATH_BOUNDS_DECIDER相关配置

modules/planning/conf/planning_config.pb.txt中有相关配置。

default_task_config: {
  task_type: PATH_BOUNDS_DECIDER
  path_bounds_decider_config {
    is_lane_borrowing: false
    is_pull_over: false
    is_extend_lane_bounds_to_include_adc: false
    pull_over_destination_to_adc_buffer: 25.0
    pull_over_destination_to_pathend_buffer: 4.0
    pull_over_road_edge_buffer: 0.15
    pull_over_approach_lon_distance_adjust_factor: 1.5
  }
}

modules/planning/proto/task_config.proto中也有相关参数

// PathBoundsDeciderConfig

message PathBoundsDeciderConfig {
  optional bool is_lane_borrowing = 1;
  optional bool is_pull_over = 2;
  // not search pull-over position if the destination is within this distance
  // from ADC
  optional double pull_over_destination_to_adc_buffer = 3 [default = 25.0];
  // not search pull-over position if the destination is within this distance to
  // path-end
  optional double pull_over_destination_to_pathend_buffer = 4 [default = 10.0];
  // disquality a pull-over position if the available path boundary's edge is
  // not within this distance from the road edge
  optional double pull_over_road_edge_buffer = 5 [default = 0.15];
  optional double pull_over_approach_lon_distance_adjust_factor = 6
      [default = 1.5];
  optional double adc_buffer_coeff = 7 [default = 1.0];
  optional bool is_extend_lane_bounds_to_include_adc = 8 [default = true];
}

数据结构

// modules/planning/tasks/deciders/path_bounds_decider/path_bounds_decider.cc
namespace {
// PathBoundPoint contains: (s, l_min, l_max).路径边界点
using PathBoundPoint = std::tuple<double, double, double>;
// PathBound contains a vector of PathBoundPoints.路径边界
using PathBound = std::vector<PathBoundPoint>;
// ObstacleEdge contains: (is_start_s, s, l_min, l_max, obstacle_id).障碍物的边
using ObstacleEdge = std::tuple<int, double, double, double, std::string>;
}  // namespace

参数设置

// modules/planning/tasks/deciders/path_bounds_decider/path_bounds_decider.h
// s方向的距离
constexpr double kPathBoundsDeciderHorizon = 100.0;
// s方向的间隔
constexpr double kPathBoundsDeciderResolution = 0.5;
// Lane宽度
constexpr double kDefaultLaneWidth = 5.0;
// Road的道路
constexpr double kDefaultRoadWidth = 20.0;
// TODO(all): Update extra tail point base on vehicle speed.
constexpr int kNumExtraTailBoundPoint = 20;
constexpr double kPulloverLonSearchCoeff = 1.5;
constexpr double kPulloverLatSearchCoeff = 1.25;

PATH_BOUNDS_DECIDER总体流程

总体流程依然先看Process部分
在这里插入图片描述
Process方法中,分四种场景对路径边界进行计算,按照处理的顺序分别是:fallbackpull-overlane-changeregular。 其中regular场景根据是否借道又分为LEFT_BORROW, NO_BORROW, RIGHT_BORROW

fallback场景的path bounds一定会生成,另外三种看情况,都是需要if判断。

InitPathBoundsDecider

InitPathBoundsDecider初始化planning_start_point、获取ADC S/L坐标信息、获取ADC当前所在的车道线宽度。

void PathBoundsDecider::InitPathBoundsDecider(
    const Frame& frame, const ReferenceLineInfo& reference_line_info) {
  const ReferenceLine& reference_line = reference_line_info.reference_line();
  common::TrajectoryPoint planning_start_point = frame.PlanningStartPoint();
  if (FLAGS_use_front_axe_center_in_path_planning) {
    planning_start_point =
        InferFrontAxeCenterFromRearAxeCenter(planning_start_point);
  }
  ADEBUG << "Plan at the starting point: x = "
         << planning_start_point.path_point().x()
         << ", y = " << planning_start_point.path_point().y()
         << ", and angle = " << planning_start_point.path_point().theta();

  // Initialize some private variables.
  // ADC s/l info.
  auto adc_sl_info = reference_line.ToFrenetFrame(planning_start_point);
  adc_frenet_s_ = adc_sl_info.first[0];
  adc_frenet_l_ = adc_sl_info.second[0];
  adc_frenet_sd_ = adc_sl_info.first[1];
  adc_frenet_ld_ = adc_sl_info.second[1] * adc_frenet_sd_;
  double offset_to_map = 0.0;
  reference_line.GetOffsetToMap(adc_frenet_s_, &offset_to_map);
  adc_l_to_lane_center_ = adc_frenet_l_ + offset_to_map;

  // ADC's lane width.
  double lane_left_width = 0.0;
  double lane_right_width = 0.0;
  if (!reference_line.GetLaneWidth(adc_frenet_s_, &lane_left_width,
                                   &lane_right_width)) {
    AWARN << "Failed to get lane width at planning start point.";
    adc_lane_width_ = kDefaultLaneWidth;
  } else {
    adc_lane_width_ = lane_left_width + lane_right_width;
  }
}

1. fallback

无论当前处于何种场景,都会调用GenerateFallbackPathBound() 来生成备用的path bound,在计算FallbackPathBound时不考虑障碍物边界,仅使用道路边界,并考虑借道信息来进行计算。
在这里插入图片描述
fallback部分主要包含两个函数,InitPathBoundaryGetBoundaryFromLanesAndADC。fallback是备选的方案,只考虑adc信息和静态道路信息。

GenerateFallbackPathBound

Status PathBoundsDecider::GenerateFallbackPathBound(
    const ReferenceLineInfo& reference_line_info, PathBound* const path_bound) {
  // 1. Initialize the path boundaries to be an indefinitely large area.
  if (!InitPathBoundary(reference_line_info, path_bound)) {...
  // PathBoundsDebugString(*path_bound);

  // 2. Decide a rough boundary based on lane info and ADC's position
  std::string dummy_borrow_lane_type;
  if (!GetBoundaryFromLanesAndADC(reference_line_info,
                                  LaneBorrowInfo::NO_BORROW, 0.5, path_bound,
                                  &dummy_borrow_lane_type, true)) {...
  // PathBoundsDebugString(*path_bound);
  ADEBUG << "Completed generating fallback path boundaries.";
  return Status::OK();
}

InitPathBoundary

InitPathBoundary从adc当前位置开始,以0.5m为间隔取点,直到终点,将 [左, 右] 边界设置为double的 [lowerst, max]。

bool PathBoundsDecider::InitPathBoundary(
  ...
  // Starting from ADC's current position, increment until the horizon, and
  // set lateral bounds to be infinite at every spot.
  // 从adc当前位置开始,以0.5m为间隔取点,直到终点,将 [左, 右] 边界设置为double的 [lowerst, max]
  for (double curr_s = adc_frenet_s_;
       curr_s < std::fmin(adc_frenet_s_ +
                              std::fmax(kPathBoundsDeciderHorizon,
                                        reference_line_info.GetCruiseSpeed() *
                                            FLAGS_trajectory_time_length),
                          reference_line.Length());
       curr_s += kPathBoundsDeciderResolution) {
    path_bound->emplace_back(curr_s, std::numeric_limits<double>::lowest(),
                             std::numeric_limits<double>::max());
  }
...}

GetBoundaryFromLanesAndADC

GetBoundaryFromLanesAndADC首先获取当前车道的宽度;再根据是否发生借道的决策,获取相邻车道的宽度(包括对向车道以及同向相邻车道);再根据ADC的位置和速度计算边界;最后更新边界。

// TODO(jiacheng): this function is to be retired soon.
bool PathBoundsDecider::GetBoundaryFromLanesAndADC(
  ...
  for (size_t i = 0; i < path_bound->size(); ++i) {
    double curr_s = std::get<0>((*path_bound)[i]);
    // 1. Get the current lane width at current point.获取当前点车道的宽度
    if (!reference_line.GetLaneWidth(curr_s, &curr_lane_left_width,
                                     &curr_lane_right_width)) {
      AWARN << "Failed to get lane width at s = " << curr_s;
      curr_lane_left_width = past_lane_left_width;
      curr_lane_right_width = past_lane_right_width;
    } else {...}

    // 2. Get the neighbor lane widths at the current point.获取当前点相邻车道的宽度
    double curr_neighbor_lane_width = 0.0;
    if (CheckLaneBoundaryType(reference_line_info, curr_s, lane_borrow_info)) {
      hdmap::Id neighbor_lane_id;
      if (lane_borrow_info == LaneBorrowInfo::LEFT_BORROW) {
        // 借左车道
        ...
      } else if (lane_borrow_info == LaneBorrowInfo::RIGHT_BORROW) {
        // 借右车道
        ...
      }
    }

    // 3. 根据道路宽度,adc的位置和速度计算合适的边界。
    static constexpr double kMaxLateralAccelerations = 1.5;
    double offset_to_map = 0.0;
    reference_line.GetOffsetToMap(curr_s, &offset_to_map);

    double ADC_speed_buffer = (adc_frenet_ld_ > 0 ? 1.0 : -1.0) *
                              adc_frenet_ld_ * adc_frenet_ld_ /
                              kMaxLateralAccelerations / 2.0;
    // 向左车道借到,左边界会变成左侧车道左边界
    double curr_left_bound_lane =
        curr_lane_left_width + (lane_borrow_info == LaneBorrowInfo::LEFT_BORROW
                                    ? curr_neighbor_lane_width
                                    : 0.0);
    // 和上面类似
    double curr_right_bound_lane =
        -curr_lane_right_width -
        (lane_borrow_info == LaneBorrowInfo::RIGHT_BORROW
             ? curr_neighbor_lane_width
             : 0.0);

    double curr_left_bound = 0.0;  // 左边界
    double curr_right_bound = 0.0;  // 右边界
    // 计算左边界和右边界
    if (config_.path_bounds_decider_config()
            .is_extend_lane_bounds_to_include_adc() ||
        is_fallback_lanechange) {
      // extend path bounds to include ADC in fallback or change lane path
      // bounds.
      double curr_left_bound_adc =
          std::fmax(adc_l_to_lane_center_,
                    adc_l_to_lane_center_ + ADC_speed_buffer) +
          GetBufferBetweenADCCenterAndEdge() + ADC_buffer;
      curr_left_bound =
          std::fmax(curr_left_bound_lane, curr_left_bound_adc) - offset_to_map;

      double curr_right_bound_adc =
          std::fmin(adc_l_to_lane_center_,
                    adc_l_to_lane_center_ + ADC_speed_buffer) -
          GetBufferBetweenADCCenterAndEdge() - ADC_buffer;
      curr_right_bound =
          std::fmin(curr_right_bound_lane, curr_right_bound_adc) -
          offset_to_map;
    } else {
      curr_left_bound = curr_left_bound_lane - offset_to_map;
      curr_right_bound = curr_right_bound_lane - offset_to_map;
    }

    // 4. 更新边界.
    if (!UpdatePathBoundaryWithBuffer(i, curr_left_bound, curr_right_bound,
                                      path_bound, is_left_lane_boundary,
                                      is_right_lane_boundary)) {
      path_blocked_idx = static_cast<int>(i);
    }
... }

PS:
涉及到的几个参数:
(1)ADC_speed_buffer,我的理解是车辆以最大横向加速度将横向速度降为0所经过的距离。 l a t = V l a t 2 2 a lat=\frac {{V_{lat}}^2} {2a} lat=2aVlat2

    double ADC_speed_buffer = (adc_frenet_ld_ > 0 ? 1.0 : -1.0) *
                              adc_frenet_ld_ * adc_frenet_ld_ /
                              kMaxLateralAccelerations / 2.0;

(2) curr_left_bound_lanecurr_right_bound_lane基于车道线的左右边界,如果产生变道,则加上相邻车道的宽度。

    double curr_left_bound_lane =
        curr_lane_left_width + (lane_borrow_info == LaneBorrowInfo::LEFT_BORROW
                                    ? curr_neighbor_lane_width
                                    : 0.0);

    double curr_right_bound_lane =
        -curr_lane_right_width -
        (lane_borrow_info == LaneBorrowInfo::RIGHT_BORROW
             ? curr_neighbor_lane_width
             : 0.0);

(3)curr_left_bound_adc基于自车产生的边界。根据ADC_speed_buffer,ADC_buffer(0.5,可以认为是横向安全区间),半车宽,adc_l_to_lane_center_(自车相对于车道中心的偏移量)计算。

      double curr_left_bound_adc =
          std::fmax(adc_l_to_lane_center_,
                    adc_l_to_lane_center_ + ADC_speed_buffer) +
          GetBufferBetweenADCCenterAndEdge() + ADC_buffer;

计算示意图大致如下:
在这里插入图片描述
(4)offset_to_map:相对地图的偏移量。

UpdatePathBoundaryWithBuffer

UpdatePathBoundaryWithBuffer首先计算缓冲边界(实际意义就是将左右边界各收缩半个车宽),若(l_min > l_max),即右边界大于左边界,则发生block,不更新。

bool PathBoundsDecider::UpdatePathBoundaryWithBuffer(
    size_t idx, double left_bound, double right_bound,
    PathBound* const path_boundaries, bool is_left_lane_bound,
    bool is_right_lane_bound) {
  // substract vehicle width when bound does not come from the lane boundary
  // 计算缓冲边界,默认是1.0
  const double default_adc_buffer_coeff = 1.0;
  double left_adc_buffer_coeff =
      (is_left_lane_bound
           ? config_.path_bounds_decider_config().adc_buffer_coeff()
           : default_adc_buffer_coeff);
  double right_adc_buffer_coeff =
      (is_right_lane_bound
           ? config_.path_bounds_decider_config().adc_buffer_coeff()
           : default_adc_buffer_coeff);

  // Update the right bound (l_min):
  double new_l_min =
      std::fmax(std::get<1>((*path_boundaries)[idx]),
                right_bound + right_adc_buffer_coeff *
                                  GetBufferBetweenADCCenterAndEdge());
  // Update the left bound (l_max):
  double new_l_max = std::fmin(
      std::get<2>((*path_boundaries)[idx]),
      left_bound - left_adc_buffer_coeff * GetBufferBetweenADCCenterAndEdge());

  // Check if ADC is blocked.
  // If blocked, don't update anything, return false.
  if (new_l_min > new_l_max) {
    ADEBUG << "Path is blocked at idx = " << idx;
    return false;
  }
  // Otherwise, update path_boundaries and center_line; then return true.
  std::get<1>((*path_boundaries)[idx]) = new_l_min;
  std::get<2>((*path_boundaries)[idx]) = new_l_max;
  return true;
}
TrimPathBounds

TrimPathBounds截断block之后的边界点。

2. pull over

在这里插入图片描述

GeneratePullOverPathBound

核心逻辑在GeneratePullOverPathBound中。
InitPathBoundary在fallback部分已经讨论过了,接着来看GetBoundaryFromRoads

GetBoundaryFromRoads

GetBoundaryFromRoads主要完成:获取道路边界;更新道路边界;裁剪block之后的边界点。

GetBoundaryFromRoads根据道路信息确定一个大致的边界。返回的边界是相对于车道中心(而不是reference_line)的,尽管在大多数情况下reference_line与车道中心的偏差可以忽略不计。

UpdatePullOverBoundaryByLaneBoundary

之后调用UpdatePullOverBoundaryByLaneBoundary更新pull over的边界。pull over有两种状态:PULL_OVEREMERGENCY_PULL_OVER
对于PULL_OVER,选取车道左边界作为边界。对于EMERGENCY_PULL_OVER,选取左/右车道边界作为边界,因为可能会在对向车道停车。

GetBoundaryFromStaticObstacles

根据静态障碍物对边界进行调整。它将确保边界不包含任何静态障碍,这样之后优化时生成的路径就不会与任何静态障碍碰撞。

在这里插入图片描述

SearchPullOverPosition

它的目的是搜索停车点,为了能够容纳车的尺寸,因为要先搜索可以停车的区域,然后在该区域内取一点作为停车点。搜索区域时,要先确定一个端点,然后向前或向后考察另一个端点,以及考察两端点之间的区域是否符合要求。

搜索pull over位置的过程:

  • 根据pull_over_status.pull_over_type()判断是前向搜索(pull
    over开头第一个点),还是后向搜索(pull over末尾后一个点)
  • 两层循环,外层控制搜索的索引idx,内层控制进一步的索引(前向idx+1,后向idx-1)。
  • 根据内外两层循环的索引,判断搜索到的空间是否满足宽度和长度要求,判断是否可以pull over
bool PathBoundsDecider::SearchPullOverPosition(
    const Frame& frame, const ReferenceLineInfo& reference_line_info,
    const std::vector<std::tuple<double, double, double>>& path_bound,
    std::tuple<double, double, double, int>* const pull_over_configuration) {
  const auto& pull_over_status =
      injector_->planning_context()->planning_status().pull_over();

  // 搜索方向,默认前向搜索
  bool search_backward = false;  // search FORWARD by default

  double pull_over_s = 0.0;
  if (pull_over_status.pull_over_type() ==
      PullOverStatus::EMERGENCY_PULL_OVER) {...}

  int idx = 0;
  if (search_backward) {
    // 后向搜索,定位pull over末尾的一个点.
    idx = static_cast<int>(path_bound.size()) - 1;
    while (idx >= 0 && std::get<0>(path_bound[idx]) > pull_over_s) {
      --idx;
    }
  } else {
    // 前向搜索,定位emergency pull over开头后的第一个点.
    while (idx < static_cast<int>(path_bound.size()) &&
           std::get<0>(path_bound[idx]) < pull_over_s) {
      ++idx;
    }
  }
  
  // 为pull over搜索到一个可行的位置,主要是确定该区域的宽度和长度
  const double pull_over_space_length =
      kPulloverLonSearchCoeff *
          VehicleConfigHelper::GetConfig().vehicle_param().length() -
      FLAGS_obstacle_lon_start_buffer - FLAGS_obstacle_lon_end_buffer;
  const double pull_over_space_width =
      (kPulloverLatSearchCoeff - 1.0) *
      VehicleConfigHelper::GetConfig().vehicle_param().width();
  const double adc_half_width =
      VehicleConfigHelper::GetConfig().vehicle_param().width() / 2.0;

  // 2. Find a window that is close to road-edge.
  /*
    这里用了内外两层循环进行搜索,外层循环控制搜索的开始的端点idx。
    内层控制另一个端点。根据找到的两个端点,判断区域是否可以pull over
  */
  bool has_a_feasible_window = false;
  while ((search_backward && idx >= 0 &&
          std::get<0>(path_bound[idx]) - std::get<0>(path_bound.front()) >
              pull_over_space_length) ||
         (!search_backward && idx < static_cast<int>(path_bound.size()) &&
          std::get<0>(path_bound.back()) - std::get<0>(path_bound[idx]) >
              pull_over_space_length)) {

    while ((search_backward && j >= 0 &&
            std::get<0>(path_bound[idx]) - std::get<0>(path_bound[j]) <
                pull_over_space_length) ||
           (!search_backward && j < static_cast<int>(path_bound.size()) &&
            std::get<0>(path_bound[j]) - std::get<0>(path_bound[idx]) <
                pull_over_space_length)) {...}
    
    // 找到可行区域,获取停车区域的位置和姿态
    if (is_feasible_window) {
    ...
    break;}
    ...}  // 外层while
...
}

3. lane change

在这里插入图片描述
核心逻辑在GenerateLaneChangePathBound函数中,与前面的场景计算流程大同小异。主要核心部分在GetBoundaryFromLaneChangeForbiddenZone部分。

GenerateLaneChangePathBound

Status PathBoundsDecider::GenerateLaneChangePathBound(
    const ReferenceLineInfo& reference_line_info,
    std::vector<std::tuple<double, double, double>>* const path_bound) {
  // 1.初始化,和前面的步骤类似
  if (!InitPathBoundary(reference_line_info, path_bound)) {...}


  // 2. 根据道路和adc的信息获取一个大致的路径边界
  std::string dummy_borrow_lane_type;
  if (!GetBoundaryFromLanesAndADC(reference_line_info,
                                  LaneBorrowInfo::NO_BORROW, 0.1, path_bound,
                                  &dummy_borrow_lane_type, true)) {...}
 

  // 3. Remove the S-length of target lane out of the path-bound.
  GetBoundaryFromLaneChangeForbiddenZone(reference_line_info, path_bound);


  // 根据静态障碍物调整边界.
  if (!GetBoundaryFromStaticObstacles(reference_line_info.path_decision(),
                                      path_bound, &blocking_obstacle_id)) {...}
  ...
}

GetBoundaryFromLaneChangeForbiddenZone

GetBoundaryFromLaneChangeForbiddenZone函数运行流程如下:

  • 如果当前位置可以变道,则直接变道
  • 如果有一个lane-change的起点,则直接使用它
  • 逐个检查变道前的点的边界,改变边界的值(如果已经过了变道点,则返回)
void PathBoundsDecider::GetBoundaryFromLaneChangeForbiddenZone(
    const ReferenceLineInfo& reference_line_info, PathBound* const path_bound) {
  // Sanity checks.
  CHECK_NOTNULL(path_bound);
  const ReferenceLine& reference_line = reference_line_info.reference_line();

  // If there is a pre-determined lane-change starting position, then use it;
  // otherwise, decide one.
  auto* lane_change_status = injector_->planning_context()
                                 ->mutable_planning_status()
                                 ->mutable_change_lane();
  // 1.当前位置直接变道。
  if (lane_change_status->is_clear_to_change_lane()) {
    ADEBUG << "Current position is clear to change lane. No need prep s.";
    lane_change_status->set_exist_lane_change_start_position(false);
    return;
  }
  double lane_change_start_s = 0.0;
  // 2.如果已经有一个lane-change的起点,就直接使用它,否则再找一个
  if (lane_change_status->exist_lane_change_start_position()) {
    common::SLPoint point_sl;
    reference_line.XYToSL(lane_change_status->lane_change_start_position(),
                          &point_sl);
    lane_change_start_s = point_sl.s();
  } else {
    // TODO(jiacheng): train ML model to learn this.
    // 设置为adc前方一段距离为变道起始点
    lane_change_start_s = FLAGS_lane_change_prepare_length + adc_frenet_s_;
    
    // Update the decided lane_change_start_s into planning-context.
    // 更新变道起始点的信息
    common::SLPoint lane_change_start_sl;
    lane_change_start_sl.set_s(lane_change_start_s);
    lane_change_start_sl.set_l(0.0);
    common::math::Vec2d lane_change_start_xy;
    reference_line.SLToXY(lane_change_start_sl, &lane_change_start_xy);
    lane_change_status->set_exist_lane_change_start_position(true);
    lane_change_status->mutable_lane_change_start_position()->set_x(
        lane_change_start_xy.x());
    lane_change_status->mutable_lane_change_start_position()->set_y(
        lane_change_start_xy.y());
  }

  // Remove the target lane out of the path-boundary, up to the decided S.
  if (lane_change_start_s < adc_frenet_s_) {
    // If already passed the decided S, then return.
    // lane_change_status->set_exist_lane_change_start_position(false);
    return;
  }
  // 逐个检查变道前的点的边界,改变边界的值
  for (size_t i = 0; i < path_bound->size(); ++i) {
    double curr_s = std::get<0>((*path_bound)[i]);
    if (curr_s > lane_change_start_s) {
      break;
    }
    double curr_lane_left_width = 0.0;
    double curr_lane_right_width = 0.0;
    double offset_to_map = 0.0;
    reference_line.GetOffsetToMap(curr_s, &offset_to_map);
    if (reference_line.GetLaneWidth(curr_s, &curr_lane_left_width,
                                    &curr_lane_right_width)) {
      double offset_to_lane_center = 0.0;
      reference_line.GetOffsetToMap(curr_s, &offset_to_lane_center);
      curr_lane_left_width += offset_to_lane_center;
      curr_lane_right_width -= offset_to_lane_center;
    }
    curr_lane_left_width -= offset_to_map;
    curr_lane_right_width += offset_to_map;

    std::get<1>((*path_bound)[i]) =
        adc_frenet_l_ > curr_lane_left_width   //右变道已跨过车道线,设定右界限
            ? curr_lane_left_width + GetBufferBetweenADCCenterAndEdge()
            : std::get<1>((*path_bound)[i]);
    std::get<1>((*path_bound)[i]) =
        std::fmin(std::get<1>((*path_bound)[i]), adc_frenet_l_ - 0.1);
    std::get<2>((*path_bound)[i]) =
        adc_frenet_l_ < -curr_lane_right_width
            ? -curr_lane_right_width - GetBufferBetweenADCCenterAndEdge()
            : std::get<2>((*path_bound)[i]);  //左变道已跨过车道线,设定左界限
    std::get<2>((*path_bound)[i]) =
        std::fmax(std::get<2>((*path_bound)[i]), adc_frenet_l_ + 0.1);
  }
}

PS:变道时是以相邻车道的参考线作为参考线。以向右变道为例,变道前(指跨过车道线线前adc_frenet_l_ > curr_lane_left_width),使用原先的path bound,不给右侧留空间;变道之后,再进行更新。

4. regular

在这里插入图片描述
代码流程如下:

Status PathBoundsDecider::GenerateRegularPathBound(
    const ReferenceLineInfo& reference_line_info,
    const LaneBorrowInfo& lane_borrow_info, PathBound* const path_bound,
    std::string* const blocking_obstacle_id,
    std::string* const borrow_lane_type) {
  // 1.初始化边界.
  if (!InitPathBoundary(reference_line_info, path_bound)) {...}


  // 2.根据adc位置和lane信息确定大致的边界
  if (!GetBoundaryFromLanesAndADC(reference_line_info, lane_borrow_info, 0.1,
                                  path_bound, borrow_lane_type)) {...}
  // PathBoundsDebugString(*path_bound);

  // 3.根据障碍物调整道路边界
  if (!GetBoundaryFromStaticObstacles(reference_line_info.path_decision(),
                                      path_bound, blocking_obstacle_id)) {...}
  ...
}

流程和上面的几个基本类似,借道有三种类型

  enum class LaneBorrowInfo {
    LEFT_BORROW,
    NO_BORROW,
    RIGHT_BORROW,
  };

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.coloradmin.cn/o/924608.html

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈,一经查实,立即删除!

相关文章

自定义loadbalance实现feignclient的自定义路由

自定义loadbalance实现feignclient的自定义路由 项目背景 服务A有多个同事同时开发&#xff0c;每个同事都在dev或者test环境发布自己的代码&#xff0c;注册到注册中心有好几个(本文nacos为例)&#xff0c;这时候调用feign可能会导致请求到不同分支的服务上面&#xff0c;会…

图数据库Neo4j学习五渲染图数据库neo4jd3

文章目录 1.现成的工具2.Neo4j JavaScript Driver3.neovis4.neo4jd34.1neo4jd3和neovis对比4.2获取neo4jd34.3neo4jd3的数据结构4.4Spring data neo4.4.1 定义返回数据格式4.4.1.1NeoResults4.4.1.2GraphVO4.4.1.3NodeVO4.4.1.4ShipVO 4.4.2 SDN查询解析4.4.2.1 Repo查询语句4.…

Python可视化工具库实战

Matplotlib Matplotlib 是 Python 的可视化基础库&#xff0c;作图风格和 MATLAB 类似&#xff0c;所以称为 Matplotlib。一般学习 Python 数据可视化&#xff0c;都会从 Matplotlib 入手&#xff0c;然后再学习其他的 Python 可视化库。 Seaborn Seaborn 是一个基于 Matplo…

七大出海赛道解读,亚马逊云科技为行业客户量身打造解决方案

伴随全球化带来的新机遇和国内市场的进一步趋于饱和&#xff0c;近几年&#xff0c;中国企业出海快速升温&#xff0c;成为了新的创业风口和企业的第二增长曲线。从范围上看&#xff0c;出海市场由近及远&#xff0c;逐步扩张。从传统的东南亚市场&#xff0c;到成熟的北美、欧…

基于python+pyqt的opencv汽车分割系统

目录 一、实现和完整UI视频效果展示 主界面&#xff1a; 识别结果界面&#xff1a; 查看分割处理过程图片界面&#xff1a; 二、原理介绍&#xff1a; 加权灰度化 ​编辑 二值化 滤波降噪处理 锐化处理 边缘特征提取 图像分割 完整演示视频&#xff1a; 完整代码链…

大数据课程K6——Spark的Shuffle详解

文章作者邮箱:yugongshiye@sina.cn 地址:广东惠州 ▲ 本章节目的 ⚪ 了解Spark的定义&&特点&&目的&&优缺点; ⚪ 掌握Spark的相关参数配置; ⚪ 掌握Hadoop的插件配置; 一、Spark Shuffle详解 1. 概述 Shuffle,就是洗牌。之所以…

QtC++ 设计模式(四)——策略模式

策略模式 序言理解源码 序言 还是参考的菜鸟教程&#xff0c;会C的还是看C的方式来得舒服。 . 理解 使用符合UML规范的便于理解和回忆&#xff0c;接口其实就是普通的基类 . 源码 strategy.h /// 策略 class Strategy { public:virtual ~Strategy();/*** brief 计算* p…

AIGC ChatGPT 完成多仪表盘完成率分析

各组完成率的统计与分析的这样一个综合案例 可以使用HTML &#xff0c;JS&#xff0c;Echarts 来完成制作 我们可以借助于AIGC&#xff0c;ChatGPT 人工智能来帮我们完成代码的输出。 在ChatGPT中我们只需要发送指令就可以了。 例如&#xff1a;请使用HTMl与JS&#xff0c;…

蝴蝶翻转

蝴蝶翻转 实现一 在计算机科学和数字信号处理中&#xff0c;蝴蝶操作是一种常用于快速傅里叶变换&#xff08;FFT&#xff09;的操作。在蝴蝶算法中&#xff0c;输入数据的一部分通过特定的运算结构进行重新排列和组合&#xff0c;以便在计算FFT时实现高效处理。 蝴蝶操作的…

【seaweedfs】3、f4: Facebook’s Warm BLOB Storage System 分布式对象存储的冷热数据

论文地址 Facebook的照片、视频和其他需要可靠存储和快速访问的二进制大型对象(BLOB)的语料库非常庞大&#xff0c;而且还在继续增长。随着BLOB占用空间的增加&#xff0c;将它们存储在我们传统的存储系统-- Haystack 中变得越来越低效。为了提高我们的存储效率(以Blob的有效复…

线程池的概念及实现原理

本篇是对前面线程池具体实现过程的补充&#xff0c;实现过程可参考 线程池的实现全过程v1.0版本&#xff08;手把手创建&#xff0c;看完必掌握&#xff01;&#xff01;&#xff01;&#xff09;_竹烟淮雨的博客-CSDN博客 线程池的实现v2.0&#xff08;可伸缩线程池&#xf…

04-Numpy基础-利用数组进行数据处理

NumPy数组使你可以将许多种数据处理任务表述为简洁的数组表达式&#xff08;否则需要编 写循环&#xff09;。用数组表达式代替循环的做法&#xff0c;通常被称为矢量化。一般来说&#xff0c;矢量化 数组运算要比等价的纯Python方式快上一两个数量级&#xff08;甚至更多&…

Python代理池健壮性测试 - 压力测试和异常处理

大家好&#xff01;在构建一个可靠的Python代理池时&#xff0c;除了实现基本功能外&#xff0c;我们还需要进行一系列健壮性测试来确保其能够稳定运行&#xff0c;并具备应对各种异常情况的能力。本文将介绍如何使用压力测试工具以及合适的异常处理机制来提升Python代理池的可…

vue+file-saver+xlsx+htmlToPdf+jspdf实现本地导出PDF和Excel

页面效果如下&#xff08;echarts图表按需添加&#xff0c;以下代码中没有&#xff09; 1、安装插件 npm install xlsx --save npm install file-saver --save npm install html2canvas --save npm install jspdf --save2、main.js引入html2canvas import htmlToPdf from …

Tomcat的安装与介绍

首先我们先了解一下什么是服务器&#xff1f;什么是服务器软件&#xff1f; 什么是服务器&#xff1f;安装了服务器软件的计算机。 什么是服务器软件&#xff1f; 服务器软件是一种运行在服务器操作系统上&#xff0c;用于接收和处理客户端请求&#xff0c;并提供相应服务和资…

【Go 基础篇】Go语言闭包详解:共享状态与函数式编程

介绍 在Go语言中&#xff0c;闭包是一种强大的编程特性&#xff0c;它允许函数内部包含对外部作用域变量的引用。闭包使得函数可以捕获和共享外部作用域的状态&#xff0c;实现更加灵活和复杂的编程模式。本篇博客将深入探讨Go语言中闭包的概念、用法、实现原理以及在函数式编…

【Linux】冯诺依曼体系结构思想

冯诺依曼体系结构 冯诺依曼体系结构冯诺依曼体系结构的五大部分冯诺依曼体系结构的运行过程存储器中的木桶效应扩展&#xff1a;计算机存储设备金字塔实例&#xff1a;qq聊天数据传输过程 &#x1f340;小结&#x1f340; &#x1f389;博客主页&#xff1a;小智_x0___0x_ &…

【VMware】CentOS 设置静态IP(Windows 宿主机)

文章目录 1. 更改网络适配器设置2. 配置虚拟网络编辑器3. 修改 CentOS 网络配置文件4. ping 测试结果 宿主机&#xff1a;Win11 22H2 虚拟机&#xff1a;CentOS-Stream-9-20230612.0 (Minimal) 1. 更改网络适配器设置 Win R&#xff1a;control 打开控制面板 依次点击&#x…

婉约而深刻:二叉树的中序遍历之旅

力扣题目传送门https://leetcode.cn/problems/binary-tree-inorder-traversal/ 二叉树 在这篇文章中&#xff0c;我们将深入探讨题目 "94. 二叉树的中序遍历" 的内涵与解题方法。这个问题引导我们遍历一棵二叉树&#xff0c;以中序的方式呈现节点顺序&#xff0c;从…

windows安装新openssl后依然显示旧版本

1、Windows环境下升级openssl后&#xff0c;通过指令openssl version -a查看版本号&#xff1a; 这个版本号是以前的老版本&#xff0c;不知道在哪里 2、网上找了老半天也没找到答案&#xff0c;最后通过指令 where openssl 才找到原来的openssl在哪里&#xff0c;把老的卸载掉…