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

文章目录

  • 前言
  • SPEED_BOUNDS_PRIORI_DECIDER功能简介
  • SPEED_BOUNDS_PRIORI_DECIDER相关配置
  • SPEED_BOUNDS_PRIORI_DECIDER流程
    • 将障碍物映射到ST图中
      • ComputeSTBoundary(PathDecision* path_decision)
      • ComputeSTBoundary(Obstacle* obstacle)
      • GetOverlapBoundaryPoints
      • ComputeSTBoundaryWithDecision
      • SetSpeedFallbackDistance
    • 创建速度限制
      • GetSpeedLimits
      • GetSpeedLimitFromS
  • 参考

前言

在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_STAGEenabled: truetask_type: LANE_CHANGE_DECIDERtask_type: PATH_REUSE_DECIDERtask_type: PATH_LANE_BORROW_DECIDERtask_type: PATH_BOUNDS_DECIDERtask_type: PIECEWISE_JERK_PATH_OPTIMIZERtask_type: PATH_ASSESSMENT_DECIDERtask_type: PATH_DECIDERtask_type: RULE_BASED_STOP_DECIDERtask_type: SPEED_BOUNDS_PRIORI_DECIDERtask_type: SPEED_HEURISTIC_OPTIMIZERtask_type: SPEED_DECIDERtask_type: SPEED_BOUNDS_FINAL_DECIDERtask_type: PIECEWISE_JERK_SPEED_OPTIMIZER# task_type: PIECEWISE_JERK_NONLINEAR_SPEED_OPTIMIZERtask_type: RSS_DECIDER

本文将继续介绍LaneFollow的第9个TASK——SPEED_BOUNDS_PRIORI_DECIDER

SPEED_BOUNDS_PRIORI_DECIDER功能简介

产生速度可行驶边界
在这里插入图片描述
所形成的区域是非凸的,不能用之前凸优化的方法去做,需要用动态规划的方法去做。

SPEED_BOUNDS_PRIORI_DECIDER相关配置

modules/planning/proto/task_config.proto

// SpeedBoundsDeciderConfigmessage SpeedBoundsDeciderConfig {optional double total_time = 1 [default = 7.0];optional double boundary_buffer = 2 [default = 0.1];optional double max_centric_acceleration_limit = 3 [default = 2.0];optional double minimal_kappa = 4 [default = 0.00001];optional double point_extension = 5 [default = 1.0];optional double lowest_speed = 6 [default = 2.5];optional double collision_safety_range = 7 [default = 1.0];optional double static_obs_nudge_speed_ratio = 8;optional double dynamic_obs_nudge_speed_ratio = 9;
}

modules/planning/conf/planning_config.pb.txt

default_task_config: {task_type: ST_BOUNDS_DECIDERst_bounds_decider_config {total_time: 7.0}
}

SPEED_BOUNDS_PRIORI_DECIDER流程

通过modules/planning/tasks/task_factory.cc,我们可以看到SPEED_BOUNDS_PRIORI_DECIDER按以下方式进行注册:

  task_factory_.Register(TaskConfig::SPEED_BOUNDS_PRIORI_DECIDER,[](const TaskConfig& config,const std::shared_ptr<DependencyInjector>& injector) -> Task* {return new SpeedBoundsDecider(config, injector);});

也据此可知,SPEED_BOUNDS_PRIORI_DECIDER代码实现的部分在modules/planning/tasks/deciders/speed_bounds_decider/speed_bounds_decider.cc中。

Speed bounds decider 主要完成以下任务:

  1. 将障碍物映射到ST图中
  2. 创建速度限制
  3. 获取路径长度以及时间长度作为ST边界

SpeedBoundsDecider是一个继承自Decider的派生类。当task_list中运行task::Execute()时,SpeedBoundsDecider中的Process部分开始运行。

  • 输入:frame 和reference_line_info。通过计算PathData/ReferenceLine/PathDecision/PlanningStartPoint等等信息,来得到ST_Graph。

  • Process

    • 将障碍物映射到ST图中。(boundary_mapper.ComputeSTBoundary(path_decision).code() == ErrorCode::PLANNING_ERROR) {}此处将会遍历所有的障碍物去生成ST graph。当有纵向决策产生时,会对边界进行细微调整。再此之后,所有的障碍物的st_boundary会送入一个boundaries vector之中进行保存。
    • 创建速度限制。if (!speed_limit_decider.GetSpeedLimits(path_decision->obstacles(), &speed_limit).ok())此处会遍历每一个离散的路径点并且找到其速度限制。在每一个循环中,基本速度会取决于map/path_curvature/nudge obstacles等因素。对于nudge obstacles,需要找到最近的障碍物。
    • 获取路径长度以及时间长度作为搜索边界。时间长度来自于配置文件total_time: 7.0(配置部分已有介绍)
  • 输出:boundaries/speed_limit 会存储在reference_line_info的st_graph_data中。

在这里插入图片描述

Status SpeedBoundsDecider::Process(Frame *const frame, ReferenceLineInfo *const reference_line_info) {// retrieve data from frame and reference_line_infoconst PathData &path_data = reference_line_info->path_data();const TrajectoryPoint &init_point = frame->PlanningStartPoint();const ReferenceLine &reference_line = reference_line_info->reference_line();PathDecision *const path_decision = reference_line_info->path_decision();// 1. Map obstacles into st graphauto time1 = std::chrono::system_clock::now();// 构造一个STBoundary映射对象STBoundaryMapper boundary_mapper(speed_bounds_config_, reference_line, path_data,path_data.discretized_path().Length(), speed_bounds_config_.total_time(),injector_);// FLAGS_use_st_drivable_boundary: True to use st_drivable boundary in speed planning// default: false// 清除STBoundaryif (!FLAGS_use_st_drivable_boundary) {path_decision->EraseStBoundaries();}// 将障碍物投影到ST Gragh上if (boundary_mapper.ComputeSTBoundary(path_decision).code() ==ErrorCode::PLANNING_ERROR) {const std::string msg = "Mapping obstacle failed.";AERROR << msg;return Status(ErrorCode::PLANNING_ERROR, msg);}auto time2 = std::chrono::system_clock::now();std::chrono::duration<double> diff = time2 - time1;ADEBUG << "Time for ST Boundary Mapping = " << diff.count() * 1000<< " msec.";// 所有的障碍物的st_boundary送入到一个boundaries vector之中进行保存std::vector<const STBoundary *> boundaries;for (auto *obstacle : path_decision->obstacles().Items()) {const auto &id = obstacle->Id();const auto &st_boundary = obstacle->path_st_boundary();if (!st_boundary.IsEmpty()) {if (st_boundary.boundary_type() == STBoundary::BoundaryType::KEEP_CLEAR) {path_decision->Find(id)->SetBlockingObstacle(false);} else {path_decision->Find(id)->SetBlockingObstacle(true);}boundaries.push_back(&st_boundary);}}const double min_s_on_st_boundaries = SetSpeedFallbackDistance(path_decision);// 2. Create speed limit along pathSpeedLimitDecider speed_limit_decider(speed_bounds_config_, reference_line,path_data);SpeedLimit speed_limit;if (!speed_limit_decider.GetSpeedLimits(path_decision->obstacles(), &speed_limit).ok()) {const std::string msg = "Getting speed limits failed!";AERROR << msg;return Status(ErrorCode::PLANNING_ERROR, msg);}// 3. Get path_length as s axis search bound in st graphconst double path_data_length = path_data.discretized_path().Length();// 4. Get time duration as t axis search bound in st graphconst double total_time_by_conf = speed_bounds_config_.total_time();// Load generated st graph data back to frameStGraphData *st_graph_data = reference_line_info_->mutable_st_graph_data();// Add a st_graph debug info and save the pointer to st_graph_data for// optimizer loggingauto *debug = reference_line_info_->mutable_debug();STGraphDebug *st_graph_debug = debug->mutable_planning_data()->add_st_graph();st_graph_data->LoadData(boundaries, min_s_on_st_boundaries, init_point,speed_limit, reference_line_info->GetCruiseSpeed(),path_data_length, total_time_by_conf, st_graph_debug);// Create and record st_graph debug infoRecordSTGraphDebug(*st_graph_data, st_graph_debug);return Status::OK();
}

将障碍物映射到ST图中

由Process部分代码可知,(boundary_mapper.ComputeSTBoundary(path_decision).code() == ErrorCode::PLANNING_ERROR) {}此处是函数的入口。

该部分的流程示意图如下图所示:
在这里插入图片描述

ComputeSTBoundary(PathDecision* path_decision)

ComputeSTBoundary将会遍历所有的障碍物去生成ST graph。当有纵向决策产生时,会对边界进行细微调整。再此之后,所有的障碍物的st_boundary会送入一个boundaries vector之中进行保存。

Status STBoundaryMapper::ComputeSTBoundary(PathDecision* path_decision) const {// Sanity checks.CHECK_GT(planning_max_time_, 0.0);if (path_data_.discretized_path().size() < 2) {AERROR << "Fail to get params because of too few path points. path points ""size: "<< path_data_.discretized_path().size() << ".";return Status(ErrorCode::PLANNING_ERROR,"Fail to get params because of too few path points");}// Go through every obstacle.Obstacle* stop_obstacle = nullptr;ObjectDecisionType stop_decision;double min_stop_s = std::numeric_limits<double>::max();for (const auto* ptr_obstacle_item : path_decision->obstacles().Items()) {Obstacle* ptr_obstacle = path_decision->Find(ptr_obstacle_item->Id());ACHECK(ptr_obstacle != nullptr);// If no longitudinal decision has been made, then plot it onto ST-graph.if (!ptr_obstacle->HasLongitudinalDecision()) {ComputeSTBoundary(ptr_obstacle);continue;}// If there is a longitudinal decision, then fine-tune boundary.const auto& decision = ptr_obstacle->LongitudinalDecision();if (decision.has_stop()) {// 1. Store the closest stop fence info.// TODO(all): store ref. s value in stop decision; refine the code then.common::SLPoint stop_sl_point;reference_line_.XYToSL(decision.stop().stop_point(), &stop_sl_point);const double stop_s = stop_sl_point.s();if (stop_s < min_stop_s) {stop_obstacle = ptr_obstacle;min_stop_s = stop_s;stop_decision = decision;}} else if (decision.has_follow() || decision.has_overtake() ||decision.has_yield()) {// 2. Depending on the longitudinal overtake/yield decision,//    fine-tune the upper/lower st-boundary of related obstacles.ComputeSTBoundaryWithDecision(ptr_obstacle, decision);} else if (!decision.has_ignore()) {// 3. Ignore those unrelated obstacles.AWARN << "No mapping for decision: " << decision.DebugString();}}if (stop_obstacle) {bool success = MapStopDecision(stop_obstacle, stop_decision);if (!success) {const std::string msg = "Fail to MapStopDecision.";AERROR << msg;return Status(ErrorCode::PLANNING_ERROR, msg);}}return Status::OK();
}

ComputeSTBoundary(Obstacle* obstacle)

调用GetOverlapBoundaryPoints来获取给定障碍物的上下点,然后在此基础上制定STBoundary。它还根据以前记录的决策标记边界类型。

void STBoundaryMapper::ComputeSTBoundary(Obstacle* obstacle) const {if (FLAGS_use_st_drivable_boundary) {return;}std::vector<STPoint> lower_points;std::vector<STPoint> upper_points;// Map the given obstacle onto the ST-Graph.if (!GetOverlapBoundaryPoints(path_data_.discretized_path(), *obstacle,&upper_points, &lower_points)) {return;}// 构建障碍物的boundaryauto boundary = STBoundary::CreateInstance(lower_points, upper_points);boundary.set_id(obstacle->Id());// TODO(all): potential bug here.const auto& prev_st_boundary = obstacle->path_st_boundary();const auto& ref_line_st_boundary = obstacle->reference_line_st_boundary();if (!prev_st_boundary.IsEmpty()) {boundary.SetBoundaryType(prev_st_boundary.boundary_type());} else if (!ref_line_st_boundary.IsEmpty()) {boundary.SetBoundaryType(ref_line_st_boundary.boundary_type());}obstacle->set_path_st_boundary(boundary);
}

GetOverlapBoundaryPoints

将给定的障碍物映射到ST图中。

// Map the given obstacle onto the ST-Graph. 
// The boundary is represented as upper and lower points for every s of interests.
// Note that upper_points.size() = lower_points.size()
bool STBoundaryMapper::GetOverlapBoundaryPoints(const std::vector<PathPoint>& path_points, const Obstacle& obstacle,std::vector<STPoint>* upper_points,std::vector<STPoint>* lower_points) const {// Sanity checks.DCHECK(upper_points->empty());DCHECK(lower_points->empty());if (path_points.empty()) {AERROR << "No points in path_data_.discretized_path().";return false;}const auto* planning_status = injector_->planning_context()->mutable_planning_status()->mutable_change_lane();// lane_change_obstacle_nudge_l_buffer: minimum l-distance to nudge when changing lane (meters);0.3// nonstatic_obstacle_nudge_l_buffer: minimum l-distance to nudge a non-static obstacle (meters);0.4double l_buffer =planning_status->status() == ChangeLaneStatus::IN_CHANGE_LANE? FLAGS_lane_change_obstacle_nudge_l_buffer: FLAGS_nonstatic_obstacle_nudge_l_buffer;// Draw the given obstacle on the ST-graph.const auto& trajectory = obstacle.Trajectory();if (trajectory.trajectory_point().empty()) {// For those with no predicted trajectories, just map the obstacle's// current position to ST-graph and always assume it's static.if (!obstacle.IsStatic()) {AWARN << "Non-static obstacle[" << obstacle.Id()<< "] has NO prediction trajectory."<< obstacle.Perception().ShortDebugString();}// 遍历离散路径点for (const auto& curr_point_on_path : path_points) {// planning_max_distance_ = path_data.discretized_path().Length()// 若当前点超过了规划最大距离,退出if (curr_point_on_path.s() > planning_max_distance_) {break;}// 获取障碍物的boundingboxconst Box2d& obs_box = obstacle.PerceptionBoundingBox();if (CheckOverlap(curr_point_on_path, obs_box, l_buffer)) {// If there is overlapping, then plot it on ST-graph.const double backward_distance = -vehicle_param_.front_edge_to_center();const double forward_distance = obs_box.length();double low_s =std::fmax(0.0, curr_point_on_path.s() + backward_distance);double high_s = std::fmin(planning_max_distance_,curr_point_on_path.s() + forward_distance);// It is an unrotated rectangle appearing on the ST-graph.// 静止的障碍物在ST图中就是一个矩形// TODO(jiacheng): reconsider the backward_distance, it might be// unnecessary, but forward_distance is indeed meaningful though.lower_points->emplace_back(low_s, 0.0);lower_points->emplace_back(low_s, planning_max_time_);upper_points->emplace_back(high_s, 0.0);upper_points->emplace_back(high_s, planning_max_time_);break;}}} else {// For those with predicted trajectories (moving obstacles):// 1. Subsample to reduce computation time.const int default_num_point = 50;DiscretizedPath discretized_path;if (path_points.size() > 2 * default_num_point) {const auto ratio = path_points.size() / default_num_point;std::vector<PathPoint> sampled_path_points;for (size_t i = 0; i < path_points.size(); ++i) {if (i % ratio == 0) {sampled_path_points.push_back(path_points[i]);}}discretized_path = DiscretizedPath(std::move(sampled_path_points));} else {discretized_path = DiscretizedPath(path_points);}// 2. Go through every point of the predicted obstacle trajectory.for (int i = 0; i < trajectory.trajectory_point_size(); ++i) {const auto& trajectory_point = trajectory.trajectory_point(i);// 得到障碍物在轨迹点处的boundingboxconst Box2d obs_box = obstacle.GetBoundingBox(trajectory_point);// 得到障碍物在轨迹点处的相对时间double trajectory_point_time = trajectory_point.relative_time();static constexpr double kNegtiveTimeThreshold = -1.0;// 跳过小于阈值时间的轨迹点if (trajectory_point_time < kNegtiveTimeThreshold) {continue;}// 步长const double step_length = vehicle_param_.front_edge_to_center();// FLAGS_max_trajectory_len: (unit: meter) max possible trajectory length. 1000.0auto path_len =std::min(FLAGS_max_trajectory_len, discretized_path.Length());// Go through every point of the ADC's path.for (double path_s = 0.0; path_s < path_len; path_s += step_length) {// 估计当前车辆的位置const auto curr_adc_path_point =discretized_path.Evaluate(path_s + discretized_path.front().s());if (CheckOverlap(curr_adc_path_point, obs_box, l_buffer)) {// Found overlap, start searching with higher resolutionconst double backward_distance = -step_length;const double forward_distance = vehicle_param_.length() +vehicle_param_.width() +obs_box.length() + obs_box.width();const double default_min_step = 0.1;  // in metersconst double fine_tuning_step_length = std::fmin(default_min_step, discretized_path.Length() / default_num_point);bool find_low = false;bool find_high = false;double low_s = std::fmax(0.0, path_s + backward_distance);double high_s =std::fmin(discretized_path.Length(), path_s + forward_distance);// Keep shrinking by the resolution bidirectionally until finally// locating the tight upper and lower bounds.while (low_s < high_s) {if (find_low && find_high) {break;}if (!find_low) {const auto& point_low = discretized_path.Evaluate(low_s + discretized_path.front().s());if (!CheckOverlap(point_low, obs_box, l_buffer)) {low_s += fine_tuning_step_length;} else {find_low = true;}}if (!find_high) {const auto& point_high = discretized_path.Evaluate(high_s + discretized_path.front().s());if (!CheckOverlap(point_high, obs_box, l_buffer)) {high_s -= fine_tuning_step_length;} else {find_high = true;}}}if (find_high && find_low) {lower_points->emplace_back(low_s - speed_bounds_config_.point_extension(),trajectory_point_time);upper_points->emplace_back(high_s + speed_bounds_config_.point_extension(),trajectory_point_time);}break;}}}}// Sanity checks and return.DCHECK_EQ(lower_points->size(), upper_points->size());return (lower_points->size() > 1 && upper_points->size() > 1);
}

ComputeSTBoundaryWithDecision

对于产生纵向决策的障碍物产生的ST boundary进行调整。

// Fine-tune the boundary for yielding or overtaking obstacles. 
// Increase boundary on the s-dimension or set the boundary type, etc., when necessary.
void STBoundaryMapper::ComputeSTBoundaryWithDecision(Obstacle* obstacle, const ObjectDecisionType& decision) const {DCHECK(decision.has_follow() || decision.has_yield() ||decision.has_overtake())<< "decision is " << decision.DebugString()<< ", but it must be follow or yield or overtake.";std::vector<STPoint> lower_points;std::vector<STPoint> upper_points;if (FLAGS_use_st_drivable_boundary &&obstacle->is_path_st_boundary_initialized()) {const auto& path_st_boundary = obstacle->path_st_boundary();lower_points = path_st_boundary.lower_points();upper_points = path_st_boundary.upper_points();} else {if (!GetOverlapBoundaryPoints(path_data_.discretized_path(), *obstacle,&upper_points, &lower_points)) {return;}}auto boundary = STBoundary::CreateInstance(lower_points, upper_points);// get characteristic_length and boundary_type.STBoundary::BoundaryType b_type = STBoundary::BoundaryType::UNKNOWN;double characteristic_length = 0.0;if (decision.has_follow()) {characteristic_length = std::fabs(decision.follow().distance_s());b_type = STBoundary::BoundaryType::FOLLOW;} else if (decision.has_yield()) {characteristic_length = std::fabs(decision.yield().distance_s());boundary = STBoundary::CreateInstance(lower_points, upper_points).ExpandByS(characteristic_length);b_type = STBoundary::BoundaryType::YIELD;} else if (decision.has_overtake()) {characteristic_length = std::fabs(decision.overtake().distance_s());b_type = STBoundary::BoundaryType::OVERTAKE;} else {DCHECK(false) << "Obj decision should be either yield or overtake: "<< decision.DebugString();}boundary.SetBoundaryType(b_type);boundary.set_id(obstacle->Id());boundary.SetCharacteristicLength(characteristic_length);obstacle->set_path_st_boundary(boundary);
}

SetSpeedFallbackDistance

找到障碍物路径上最低的 s 值,该 s 值将用作速度回退的距离。

double SpeedBoundsDecider::SetSpeedFallbackDistance(PathDecision *const path_decision) {// Set min_s_on_st_boundaries to guide speed fallback.static constexpr double kEpsilon = 1.0e-6;double min_s_non_reverse = std::numeric_limits<double>::infinity();double min_s_reverse = std::numeric_limits<double>::infinity();// 遍历障碍物for (auto *obstacle : path_decision->obstacles().Items()) {const auto &st_boundary = obstacle->path_st_boundary();// 障碍物ST边界为空,跳过if (st_boundary.IsEmpty()) {continue;}// 获取st边界底部左侧点和右侧点的s值,并选择较小的值作为最低的s值const auto left_bottom_point_s = st_boundary.bottom_left_point().s();const auto right_bottom_point_s = st_boundary.bottom_right_point().s();const auto lowest_s = std::min(left_bottom_point_s, right_bottom_point_s);// 如果左侧点的 s 值减去右侧点的 s 值大于 kEpsilon(即左侧点在右侧点之后),则说明这是一个反向行驶的边界if (left_bottom_point_s - right_bottom_point_s > kEpsilon) {// 更新 min_s_reverse,将其设置为最低的 s 值if (min_s_reverse > lowest_s) {min_s_reverse = lowest_s;}} else if (min_s_non_reverse > lowest_s) {// 更新 min_s_non_reverse,将其设置为最低的 s 值。min_s_non_reverse = lowest_s;}}min_s_reverse = std::max(min_s_reverse, 0.0);min_s_non_reverse = std::max(min_s_non_reverse, 0.0);return min_s_non_reverse > min_s_reverse ? 0.0 : min_s_non_reverse;
}

创建速度限制

SpeedLimits来源于三个部分:

  1. 来自于地图的速度限制
  2. 来自于道路曲率的速度限制
  3. 来自于Nudge障碍物的速度限制

该部分流程图如下所示:
在这里插入图片描述

GetSpeedLimits

Status SpeedLimitDecider::GetSpeedLimits(const IndexedList<std::string, Obstacle>& obstacles,SpeedLimit* const speed_limit_data) const {CHECK_NOTNULL(speed_limit_data);const auto& discretized_path = path_data_.discretized_path();const auto& frenet_path = path_data_.frenet_frame_path();// 遍历离散路径点for (uint32_t i = 0; i < discretized_path.size(); ++i) {const double path_s = discretized_path.at(i).s();const double reference_line_s = frenet_path.at(i).s();if (reference_line_s > reference_line_.Length()) {AWARN << "path w.r.t. reference line at [" << reference_line_s<< "] is LARGER than reference_line_ length ["<< reference_line_.Length() << "]. Please debug before proceeding.";break;}// (1) speed limit from mapdouble speed_limit_from_reference_line =reference_line_.GetSpeedLimitFromS(reference_line_s);// (2) speed limit from path curvature//  -- 2.1: limit by centripetal force (acceleration)const double speed_limit_from_centripetal_acc =// max_centric_acceleration_limit default = 2.0std::sqrt(speed_bounds_config_.max_centric_acceleration_limit() /std::fmax(std::fabs(discretized_path.at(i).kappa()),speed_bounds_config_.minimal_kappa()));// (3) speed limit from nudge obstacles// TODO(all): in future, expand the speed limit not only to obstacles with// nudge decisions.double speed_limit_from_nearby_obstacles =std::numeric_limits<double>::max();const double collision_safety_range =speed_bounds_config_.collision_safety_range();// default = 1.0// 遍历障碍物for (const auto* ptr_obstacle : obstacles.Items()) {// 跳过虚拟的障碍物if (ptr_obstacle->IsVirtual()) {continue;}// 障碍物没有横向Nudge决策,跳过if (!ptr_obstacle->LateralDecision().has_nudge()) {continue;}/* ref line:* -------------------------------*    start_s   end_s* ------|  adc   |---------------* ------------|  obstacle |------*/// TODO(all): potential problem here;// frenet and cartesian coordinates are mixed.const double vehicle_front_s =reference_line_s + vehicle_param_.front_edge_to_center();const double vehicle_back_s =reference_line_s - vehicle_param_.back_edge_to_center();const double obstacle_front_s =ptr_obstacle->PerceptionSLBoundary().end_s();const double obstacle_back_s =ptr_obstacle->PerceptionSLBoundary().start_s();// 若车辆与障碍物在s方向上没有发生重合,跳过if (vehicle_front_s < obstacle_back_s ||vehicle_back_s > obstacle_front_s) {continue;}const auto& nudge_decision = ptr_obstacle->LateralDecision().nudge();// Please notice the differences between adc_l and frenet_point_lconst double frenet_point_l = frenet_path.at(i).l();// obstacle is on the right of ego vehicle (at path point i)bool is_close_on_left =(nudge_decision.type() == ObjectNudge::LEFT_NUDGE) &&(frenet_point_l - vehicle_param_.right_edge_to_center() -collision_safety_range <ptr_obstacle->PerceptionSLBoundary().end_l());// obstacle is on the left of ego vehicle (at path point i)bool is_close_on_right =(nudge_decision.type() == ObjectNudge::RIGHT_NUDGE) &&(ptr_obstacle->PerceptionSLBoundary().start_l() -collision_safety_range <frenet_point_l + vehicle_param_.left_edge_to_center());// TODO(all): dynamic obstacles do not have nudge decisionif (is_close_on_left || is_close_on_right) {double nudge_speed_ratio = 1.0;// 静态障碍物 x 0.6if (ptr_obstacle->IsStatic()) {nudge_speed_ratio =speed_bounds_config_.static_obs_nudge_speed_ratio(); // static_obs_nudge_speed_ratio: 0.6} else {// 动态障碍物 x 0.8nudge_speed_ratio =speed_bounds_config_.dynamic_obs_nudge_speed_ratio(); // dynamic_obs_nudge_speed_ratio: 0.8}speed_limit_from_nearby_obstacles =nudge_speed_ratio * speed_limit_from_reference_line;break;}}double curr_speed_limit = 0.0;// FLAGS_enable_nudge_slowdown: True to slow down when nudge obstaclesif (FLAGS_enable_nudge_slowdown) {curr_speed_limit =std::fmax(speed_bounds_config_.lowest_speed(),   // lowest_speed:2.5std::min({speed_limit_from_reference_line,speed_limit_from_centripetal_acc,speed_limit_from_nearby_obstacles}));} else {curr_speed_limit =std::fmax(speed_bounds_config_.lowest_speed(),std::min({speed_limit_from_reference_line,speed_limit_from_centripetal_acc}));}speed_limit_data->AppendSpeedLimit(path_s, curr_speed_limit);}return Status::OK();
}

设置标志位(is_close_on_left、is_close_on_right)部分的示意图如下:
在这里插入图片描述

GetSpeedLimitFromS

double ReferenceLine::GetSpeedLimitFromS(const double s) const {// 对于速度限制列表speed_limit_中已经有的部分,直接返回相应的值。for (const auto& speed_limit : speed_limit_) {if (s >= speed_limit.start_s && s <= speed_limit.end_s) {return speed_limit.speed_limit;}}const auto& map_path_point = GetReferencePoint(s);// FLAGS_planning_upper_speed_limit: Maximum speed (m/s) in planning;31.3double speed_limit = FLAGS_planning_upper_speed_limit;bool speed_limit_found = false;// 根据lane_waypoint道路的情况进行速度限制for (const auto& lane_waypoint : map_path_point.lane_waypoints()) {if (lane_waypoint.lane == nullptr) {AWARN << "lane_waypoint.lane is nullptr.";continue;}speed_limit_found = true;speed_limit =std::fmin(lane_waypoint.lane->lane().speed_limit(), speed_limit);}// 若未找到lane_waypoint.lane,根据道路类型进行限制if (!speed_limit_found) {// use default speed limit based on road_type// FLAGS_default_city_road_speed_limit: default speed limit (m/s) for city road. 35 mphspeed_limit = FLAGS_default_city_road_speed_limit;hdmap::Road::Type road_type = GetRoadType(s);if (road_type == hdmap::Road::HIGHWAY) {// FLAGS_default_highway_speed_limit: default speed limit (m/s) for highway. 65 mphspeed_limit = FLAGS_default_highway_speed_limit;}}return speed_limit;
}

参考

[1] Planning Piecewise Jerk Nonlinear Speed Optimizer Introduction
[2] Apollo规划控制学习笔记
[3] 1.10 Speed Bounds Prior Decider

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

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

相关文章

Docker搭建私有仓库并迁移

目录 方案 A、B机器安装docker 设置阿里云镜像源 安装 Docker-CE并设置为开机自动启动 A机器准备数据 拷贝数据 B机器运行redis、mysql镜像 重启docker服务 方案 准备两台机器&#xff1a;A机器&#xff08;可以连接外网&#xff09;&#xff0c;B机器&#xff08;内网机器…

图床项目进度(二)——动态酷炫首页

前言&#xff1a; 前面的文章我不是说我简单copy了站友的一个登录页吗&#xff0c;我感觉还是太单调了&#xff0c;想加一个好看的背景。 但是我前端的水平哪里够啊&#xff0c;于是在网上找了找制作动态背景的插件。 效果如下图。 如何使用 这个插件是particles.js 安装…

C语言入门篇(九)

前言   本篇分享的是部分操作符的概念与用法&#xff0c;从经典例题入手&#xff0c;带你快速了解和掌握。   收录专栏&#xff1a;浅谈C语言 操作符详解下 10. 逗号表达式11. 下标引用、函数调用和结构成员12. 表达式求值12.1 隐士类型转换12.2 算术转换12.3 操作符的属性…

多项式求逆

已知 F F F&#xff0c;求 G G G 考虑倍增 F ( x ) ∗ H ( x ) ≡ 1 ( m o d x n / 2 ) F(x) * H(x) \equiv 1 \pmod{x^{n/2}} F(x)∗H(x)≡1(modxn/2) F ( x ) ∗ G ( x ) ≡ 1 ( m o d x n / 2 ) F(x) * G(x) \equiv 1 \pmod{x^{n/2}} F(x)∗G(x)≡1(modxn/2) 假设 H H…

最大子数组和【贪心算法】

最大子数组和 给你一个整数数组 nums &#xff0c;请你找出一个具有最大和的连续子数组&#xff08;子数组最少包含一个元素&#xff09;&#xff0c;返回其最大和。 子数组 是数组中的一个连续部分。 class Solution {public int maxSubArray(int[] nums) {//记录最大结果&…

Linux土遁术之监测监测进程打开文件

分析问题过程中&#xff0c;追踪进程打开的文件可以在许多不同情况下有用&#xff0c;体现在以下几个方面&#xff1a; 故障排除和调试&#xff1a; 当程序出现问题、崩溃或异常行为时&#xff0c;追踪进程打开的文件可以帮助您找出问题的根本原因。这有助于快速定位错误&…

基于Spring Boot的住院病人管理系统设计与实现(Java+spring boot+MySQL)

获取源码或者论文请私信博主 演示视频&#xff1a; 基于Spring Boot的住院病人管理系统设计与实现&#xff08;Javaspring bootMySQL&#xff09; 使用技术&#xff1a; 前端&#xff1a;html css javascript jQuery ajax thymeleaf 微信小程序 后端&#xff1a;Java spring…

vue三级市区联动

默认返回值格式&#xff1a;all:code、name都返回 name:只返回name code:只返回code&#xff0c;level&#xff1a;可设置显示层级 1&#xff1a; 省 2&#xff1a; 省、市 3&#xff1a; 省、市、区 v-model 默认值 可以是 name: [ "天津市", "天津市",…

Debian 30 周年,生日快乐!

导读近日是 Debian 日&#xff0c;也是由伊恩-默多克&#xff08;Ian Murdock&#xff09;创立的 Debian GNU/Linux 通用操作系统和社区支持的 Debian 项目 30 周年纪念日。 不管你信不信&#xff0c;从已故的伊恩-默多克于 1993 年 8 月 16 日宣布成立 Debian 项目&#xff0c…

CentOS 7 Nacos 设置开机自动重启

一、说明 Nacos如果是手动启动的话&#xff0c;在服务器宕机或者重启后&#xff0c;没有自动运行&#xff0c;影响很多业务系统&#xff0c;需要每次手动执行命令 startup.sh -m standalone&#xff0c;才能启动 Nacos 服务&#xff0c;不能像docker服务一样&#xff0c;使用 …

博客系统后端(项目系列2)

目录 前言 &#xff1a; 1.准备工作 1.1创建项目 1.2引入依赖 1.3创建必要的目录 2.数据库设计 2.1博客数据 2.2用户数据 3.封装数据库 3.1封装数据库的连接操作 3.2创建两个表对应的实体类 3.3封装一些必要的增删改查操作 4.前后端交互逻辑的实现 4.1博客列表页 …

【ES】elasticsearch8.3.3

这里仅实践操作并根据实际问题进行记录笔记。 运行 ES8 我们需要在自己的电脑上安装好 Docker Desktop。接着我们运行如下的命令&#xff1a;出现两个异常&#xff0c;一个是需要使用winpty因为我使用win的docker desktop&#xff0c;另外一个问题是docker启动elasticsearchE…

跨屏无界 | ZlongGames 携手 Google Play Games 打造无缝游戏体验

一款经典游戏&#xff0c;会在时间的沉淀中被每一代玩家所怀念&#xff0c;经久不衰。对于紫龙游戏来讲&#xff0c;他们就是这样一群怀揣着创作出经典游戏的初心而聚集在一起的团队&#xff0c;致力于研发出被广大玩家喜爱的作品。 从 2015 年团队成立&#xff0c;到 2019 年走…

Ansible-palybook学习

目录 一.playbook介绍二.playbook格式1.书写格式2.notify介绍 一.playbook介绍 playbook 是 ansible 用于配置&#xff0c;部署&#xff0c;和管理被控节点的剧本。通过 playbook 的详细描述&#xff0c;执行其中的一系列 tasks &#xff0c;可以让远端主机达到预期的状态。pl…

Krahets 笔面试精选 88 题——40. 组合总和 II

使用深度搜索的方法&#xff1a; 由于题目说候选数组中的每个数字在每个组合只能出现一次&#xff0c;所以&#xff0c;为了避免重复&#xff0c;在开始之前对候选数组进行升序排序&#xff0c;这样优先选择小的数&#xff0c;如果当前的数都小于目标值&#xff0c;则后面的数就…

(学习笔记-调度算法)磁盘调度算法

磁盘结构&#xff1a; 常见的机械磁盘是上图左边的样子&#xff0c;中间圆的部分是磁盘的盘片&#xff0c;一般会有多个盘片&#xff0c;每个盘面都有自己的磁头。右边的图就是一个盘片的结构&#xff0c;盘片中的每一层分为多个磁道&#xff0c;每个磁道分为多个扇区&#xff…

MySQL从入门到精通【进阶篇】之 主从复制详解

文章目录 0.前言1. 主从复制简介2. 主从复制的工作流程主从复制过程中的日志文件作用&#xff08;Binary Log&#xff09;和中继日志&#xff08;Relay Log&#xff09; 3. MySQL主从复制的配置4. 参考资料 0.前言 MySQL的主从复制和读写分离是数据库领域的基本概念&#xff0…

前端vue2、vue3去掉url路由“ # ”号——nginx配置

文章目录 ⭐前言⭐vue2中router默认出现#号&#x1f496;在vue2项目中去掉&#x1f496;在vue3项目中去掉 ⭐vue打包 assetsPublicPath base 为绝对路径 /&#x1f496;vue2 配置 assetsPublicPath&#x1f496;vue3 配置 base&#x1f496;验证 ⭐nginx 配置&#x1f496; 使用…

Shell编程之流程控制

目录 if判断 case语句 for循环 while循环 if判断 语法&#xff1a; if [ 条件判断表达式 ] then 程序 elif [ 条件判断表达式 ] then 程序 else 程序 fi 注意&#xff1a; [ 条件判断表达式 ]&#xff0c;中括号和条件判断表达式之间必须有空格。if&#xff0c;elif…

SAP FI之定义财务年和财务年度变式(Fiscal Year Variants)

目录 前言 一、财务年度/财务年度变式 二、使用步骤 1.配置步骤 前言 本文主要介绍SAP会计年度和SAP会计年度变式。 一、财务年度/财务年度变式 财务年度可以具有与日历年相同的期间&#xff0c;也可以不同。中国财政年度从1月到12月&#xff0c;称为历年制&#xff0c;有…