From 89ec58b1fd42c731e234dad080bf9764f4833ea3 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 26 Sep 2023 10:48:32 +0900 Subject: [PATCH 1/8] add peeking_offset_absence_tl param Signed-off-by: Mamoru Sobue --- .../src/manager.cpp | 18 +++++++++++---- .../src/scene_intersection.cpp | 22 ++++++++++++------- .../src/scene_intersection.hpp | 7 ++++-- 3 files changed, 33 insertions(+), 14 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index e02a1e4220030..d8b41f875b00c 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -136,6 +136,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.stop_release_margin_time"); ip.occlusion.temporal_stop_before_attention_area = getOrDeclareParameter(node, ns + ".occlusion.temporal_stop_before_attention_area"); + ip.occlusion.peeking_offset_absence_tl = + getOrDeclareParameter(node, ns + ".occlusion.peeking_offset_absence_tl"); } void IntersectionModuleManager::launchNewModules( @@ -165,13 +167,21 @@ void IntersectionModuleManager::launchNewModules( continue; } - const auto associative_ids = - planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); const std::string location = ll.attributeOr("location", "else"); const bool is_private_area = (location.compare("private") == 0); + const auto associative_ids = + planning_utils::getAssociativeIntersectionLanelets(ll, lanelet_map, routing_graph); + bool has_traffic_light = false; + if (const auto tl_reg_elems = ll.regulatoryElementsAs(); + tl_reg_elems.size() != 0) { + const auto tl_reg_elem = tl_reg_elems.front(); + const auto stop_line_opt = tl_reg_elem->stopLine(); + if (!!stop_line_opt) has_traffic_light = true; + } const auto new_module = std::make_shared( - module_id, lane_id, planner_data_, intersection_param_, associative_ids, is_private_area, - enable_occlusion_detection, node_, logger_.get_child("intersection_module"), clock_); + module_id, lane_id, planner_data_, intersection_param_, associative_ids, turn_direction, + has_traffic_light, enable_occlusion_detection, is_private_area, node_, + logger_.get_child("intersection_module"), clock_); generateUUID(module_id); /* set RTC status as non_occluded status initially */ const UUID uuid = getUUID(new_module->getModuleId()); diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 89bb65f403095..a3571dd99d01d 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -65,14 +65,18 @@ static bool isTargetCollisionVehicleType( } IntersectionModule::IntersectionModule( - const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, + const int64_t module_id, const int64_t lane_id, + [[maybe_unused]] std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, - const bool is_private_area, const bool enable_occlusion_detection, rclcpp::Node & node, + const std::string & turn_direction, const bool has_traffic_light, + const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock) : SceneModuleInterface(module_id, logger, clock), node_(node), lane_id_(lane_id), associative_ids_(associative_ids), + turn_direction_(turn_direction), + has_traffic_light_(has_traffic_light), enable_occlusion_detection_(enable_occlusion_detection), occlusion_attention_divisions_(std::nullopt), is_private_area_(is_private_area), @@ -81,11 +85,10 @@ IntersectionModule::IntersectionModule( velocity_factor_.init(VelocityFactor::INTERSECTION); planner_param_ = planner_param; - const auto & assigned_lanelet = - planner_data->route_handler_->getLaneletMapPtr()->laneletLayer.get(lane_id); - turn_direction_ = assigned_lanelet.attributeOr("turn_direction", "else"); - collision_state_machine_.setMarginTime( - planner_param_.collision_detection.state_transit_margin_time); + { + collision_state_machine_.setMarginTime( + planner_param_.collision_detection.state_transit_margin_time); + } { before_creep_state_machine_.setMarginTime(planner_param_.occlusion.before_creep_stop_time); before_creep_state_machine_.setState(StateMachine::State::STOP); @@ -783,10 +786,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto & first_attention_area_opt = intersection_lanelets_.value().first_attention_area(); const auto & dummy_first_attention_area = first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; + const double peeking_offset = has_traffic_light_ + ? planner_param_.occlusion.peeking_offset + : planner_param_.occlusion.peeking_offset_absence_tl; const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin, - planner_param_.occlusion.peeking_offset, path); + peeking_offset, path); if (!intersection_stop_lines_opt) { RCLCPP_DEBUG(logger_, "failed to generate intersection_stop_lines"); return IntersectionModule::Indecisive{}; diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 550b23aa17606..139dd0f267871 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -116,6 +116,7 @@ class IntersectionModule : public SceneModuleInterface double ignore_parked_vehicle_speed_threshold; double stop_release_margin_time; bool temporal_stop_before_attention_area; + double peeking_offset_absence_tl; } occlusion; }; @@ -187,7 +188,8 @@ class IntersectionModule : public SceneModuleInterface IntersectionModule( const int64_t module_id, const int64_t lane_id, std::shared_ptr planner_data, const PlannerParam & planner_param, const std::set & associative_ids, - const bool is_private_area, const bool enable_occlusion_detection, rclcpp::Node & node, + const std::string & turn_direction, const bool has_traffic_light, + const bool enable_occlusion_detection, const bool is_private_area, rclcpp::Node & node, const rclcpp::Logger logger, const rclcpp::Clock::SharedPtr clock); /** @@ -211,7 +213,8 @@ class IntersectionModule : public SceneModuleInterface rclcpp::Node & node_; const int64_t lane_id_; const std::set associative_ids_; - std::string turn_direction_; + const std::string turn_direction_; + const bool has_traffic_light_; bool is_go_out_ = false; bool is_permanent_go_ = false; From 3681a903d58a51d181872d9f2e11f9fdcccf8b35 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Oct 2023 14:03:55 +0900 Subject: [PATCH 2/8] add OccludedAbsenceTrafficLight state Signed-off-by: Mamoru Sobue --- .../config/intersection.param.yaml | 3 + .../src/debug.cpp | 12 +- .../src/manager.cpp | 6 +- .../src/scene_intersection.cpp | 181 ++++++++++++------ .../src/scene_intersection.hpp | 38 +++- .../src/util_type.hpp | 1 + 6 files changed, 173 insertions(+), 68 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml index 4042adeb3623e..5e74e837bf186 100644 --- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml +++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml @@ -54,6 +54,9 @@ ignore_parked_vehicle_speed_threshold: 0.8333 # == 3.0km/h stop_release_margin_time: 1.5 # [s] temporal_stop_before_attention_area: false + absence_traffic_light: + creep_velocity: 1.388 # [m/s] + maximum_peeking_distance: 6.0 # [m] enable_rtc: intersection: true # If set to true, the scene modules require approval from the rtc (request to cooperate) function. If set to false, the modules can be executed without requiring rtc approval diff --git a/planning/behavior_velocity_intersection_module/src/debug.cpp b/planning/behavior_velocity_intersection_module/src/debug.cpp index fbb82d6ace175..c875611b16003 100644 --- a/planning/behavior_velocity_intersection_module/src/debug.cpp +++ b/planning/behavior_velocity_intersection_module/src/debug.cpp @@ -271,29 +271,37 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray( motion_utils::VirtualWalls IntersectionModule::createVirtualWalls() { - // TODO(Mamoru Sobue): collision stop pose depends on before/after occlusion clearance motion_utils::VirtualWalls virtual_walls; motion_utils::VirtualWall wall; - wall.style = motion_utils::VirtualWallType::stop; if (debug_data_.collision_stop_wall_pose) { + wall.style = motion_utils::VirtualWallType::stop; wall.text = "intersection"; wall.ns = "intersection" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.collision_stop_wall_pose.value(); virtual_walls.push_back(wall); } if (debug_data_.occlusion_first_stop_wall_pose) { + wall.style = motion_utils::VirtualWallType::stop; wall.text = "intersection"; wall.ns = "intersection_occlusion_first_stop" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.occlusion_first_stop_wall_pose.value(); virtual_walls.push_back(wall); } if (debug_data_.occlusion_stop_wall_pose) { + wall.style = motion_utils::VirtualWallType::stop; wall.text = "intersection_occlusion"; wall.ns = "intersection_occlusion" + std::to_string(module_id_) + "_"; wall.pose = debug_data_.occlusion_stop_wall_pose.value(); virtual_walls.push_back(wall); } + if (debug_data_.absence_traffic_light_creep_wall) { + wall.style = motion_utils::VirtualWallType::slowdown; + wall.text = "intersection_occlusion"; + wall.ns = "intersection_occlusion" + std::to_string(module_id_) + "_"; + wall.pose = debug_data_.absence_traffic_light_creep_wall.value(); + virtual_walls.push_back(wall); + } return virtual_walls; } diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp index d8b41f875b00c..d42c9b3ca2aa2 100644 --- a/planning/behavior_velocity_intersection_module/src/manager.cpp +++ b/planning/behavior_velocity_intersection_module/src/manager.cpp @@ -136,8 +136,10 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node) getOrDeclareParameter(node, ns + ".occlusion.stop_release_margin_time"); ip.occlusion.temporal_stop_before_attention_area = getOrDeclareParameter(node, ns + ".occlusion.temporal_stop_before_attention_area"); - ip.occlusion.peeking_offset_absence_tl = - getOrDeclareParameter(node, ns + ".occlusion.peeking_offset_absence_tl"); + ip.occlusion.absence_traffic_light.creep_velocity = + getOrDeclareParameter(node, ns + ".occlusion.absence_traffic_light.creep_velocity"); + ip.occlusion.absence_traffic_light.maximum_peeking_distance = getOrDeclareParameter( + node, ns + ".occlusion.absence_traffic_light.maximum_peeking_distance"); } void IntersectionModuleManager::launchNewModules( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index a3571dd99d01d..430bb964d2b9e 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -229,6 +229,23 @@ void prepareRTCByDecisionResult( return; } +template <> +void prepareRTCByDecisionResult( + const IntersectionModule::OccludedAbsenceTrafficLight & result, + const autoware_auto_planning_msgs::msg::PathWithLaneId & path, bool * default_safety, + double * default_distance, bool * occlusion_safety, double * occlusion_distance) +{ + RCLCPP_DEBUG(rclcpp::get_logger("prepareRTCByDecisionResult"), "OccludedAbsenceTrafficLight"); + const auto closest_idx = result.closest_idx; + const auto collision_stop_line_idx = result.closest_idx; + *default_safety = !result.collision_detected; + *default_distance = + motion_utils::calcSignedArcLength(path.points, closest_idx, collision_stop_line_idx); + *occlusion_safety = result.is_actually_occlusion_cleared; + *occlusion_distance = 0; + return; +} + template <> void prepareRTCByDecisionResult( const IntersectionModule::OccludedCollisionStop & result, @@ -573,6 +590,59 @@ void reactRTCApprovalByDecisionResult( return; } +template <> +void reactRTCApprovalByDecisionResult( + const bool rtc_default_approved, const bool rtc_occlusion_approved, + const IntersectionModule::OccludedAbsenceTrafficLight & decision_result, + [[maybe_unused]] const IntersectionModule::PlannerParam & planner_param, + const double baselink2front, autoware_auto_planning_msgs::msg::PathWithLaneId * path, + StopReason * stop_reason, VelocityFactorInterface * velocity_factor, util::DebugData * debug_data) +{ + RCLCPP_DEBUG( + rclcpp::get_logger("reactRTCApprovalByDecisionResult"), + "OccludedAbsenceTrafficLight, approval = (default: %d, occlusion: %d)", rtc_default_approved, + rtc_occlusion_approved); + if (!rtc_default_approved) { + const auto stop_line_idx = decision_result.closest_idx; + planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + debug_data->collision_stop_wall_pose = + planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + { + tier4_planning_msgs::msg::StopFactor stop_factor; + stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + planning_utils::appendStopReason(stop_factor, stop_reason); + velocity_factor->set( + path->points, path->points.at(decision_result.closest_idx).point.pose, + path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + } + } + if (!rtc_occlusion_approved && decision_result.temporal_stop_before_attention_required) { + const auto stop_line_idx = decision_result.first_attention_area_stop_line_idx; + planning_utils::setVelocityFromIndex(stop_line_idx, 0.0, path); + debug_data->occlusion_stop_wall_pose = + planning_utils::getAheadPose(stop_line_idx, baselink2front, *path); + { + tier4_planning_msgs::msg::StopFactor stop_factor; + stop_factor.stop_pose = path->points.at(stop_line_idx).point.pose; + planning_utils::appendStopReason(stop_factor, stop_reason); + velocity_factor->set( + path->points, path->points.at(decision_result.closest_idx).point.pose, + path->points.at(stop_line_idx).point.pose, VelocityFactor::INTERSECTION); + } + } + if (!rtc_occlusion_approved && !decision_result.temporal_stop_before_attention_required) { + const auto closest_idx = decision_result.closest_idx; + const auto peeking_limit_line = decision_result.peeking_limit_line_idx; + for (auto i = closest_idx; i <= peeking_limit_line; ++i) { + planning_utils::setVelocityFromIndex( + i, planner_param.occlusion.absence_traffic_light.creep_velocity, path); + } + debug_data->absence_traffic_light_creep_wall = + planning_utils::getAheadPose(closest_idx, baselink2front, *path); + } + return; +} + template <> void reactRTCApprovalByDecisionResult( const bool rtc_default_approved, const bool rtc_occlusion_approved, @@ -678,7 +748,8 @@ void reactRTCApproval( static std::string formatDecisionResult(const IntersectionModule::DecisionResult & decision_result) { if (std::holds_alternative(decision_result)) { - return "Indecisive"; + const auto indecisive = std::get(decision_result); + return "Indecisive because " + indecisive.error; } if (std::holds_alternative(decision_result)) { return "Safe"; @@ -698,6 +769,9 @@ static std::string formatDecisionResult(const IntersectionModule::DecisionResult if (std::holds_alternative(decision_result)) { return "OccludedCollisionStop"; } + if (std::holds_alternative(decision_result)) { + return "OccludedAbsenceTrafficLight"; + } if (std::holds_alternative(decision_result)) { return "TrafficLightArrowSolidOn"; } @@ -750,13 +824,12 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const auto interpolated_path_info_opt = util::generateInterpolatedPath( lane_id_, associative_ids_, *path, planner_param_.common.path_interpolation_ds, logger_); if (!interpolated_path_info_opt) { - RCLCPP_DEBUG(logger_, "splineInterpolate failed"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"splineInterpolate failed"}; } const auto & interpolated_path_info = interpolated_path_info_opt.value(); if (!interpolated_path_info.lane_id_interval) { - RCLCPP_WARN(logger_, "Path has no interval on intersection lane %ld", lane_id_); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{ + "Path has no interval on intersection lane " + std::to_string(lane_id_)}; } const auto & current_pose = planner_data_->current_odometry->pose; @@ -769,33 +842,33 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( planner_param_.occlusion.occlusion_attention_area_length, planner_param_.common.consider_wrong_direction_vehicle); } + auto & intersection_lanelets = intersection_lanelets_.value(); + const auto traffic_prioritized_level = util::getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map); const bool is_prioritized = traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED; - intersection_lanelets_.value().update(is_prioritized, interpolated_path_info); + intersection_lanelets.update(is_prioritized, interpolated_path_info); - const auto & conflicting_lanelets = intersection_lanelets_.value().conflicting(); - const auto & first_conflicting_area_opt = intersection_lanelets_.value().first_conflicting_area(); + const auto & conflicting_lanelets = intersection_lanelets.conflicting(); + const auto & first_conflicting_area_opt = intersection_lanelets.first_conflicting_area(); if (conflicting_lanelets.empty() || !first_conflicting_area_opt) { - RCLCPP_DEBUG(logger_, "conflicting area is empty"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"conflicting area is empty"}; } const auto first_conflicting_area = first_conflicting_area_opt.value(); - const auto & first_attention_area_opt = intersection_lanelets_.value().first_attention_area(); + const auto & first_attention_area_opt = intersection_lanelets.first_attention_area(); const auto & dummy_first_attention_area = first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; - const double peeking_offset = has_traffic_light_ - ? planner_param_.occlusion.peeking_offset - : planner_param_.occlusion.peeking_offset_absence_tl; + const double peeking_offset = + has_traffic_light_ ? planner_param_.occlusion.peeking_offset + : planner_param_.occlusion.absence_traffic_light.maximum_peeking_distance; const auto intersection_stop_lines_opt = util::generateIntersectionStopLines( first_conflicting_area, dummy_first_attention_area, planner_data_, interpolated_path_info, planner_param_.stuck_vehicle.use_stuck_stopline, planner_param_.common.stop_line_margin, peeking_offset, path); if (!intersection_stop_lines_opt) { - RCLCPP_DEBUG(logger_, "failed to generate intersection_stop_lines"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"failed to generate intersection_stop_lines"}; } const auto & intersection_stop_lines = intersection_stop_lines_opt.value(); const auto @@ -803,14 +876,13 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = intersection_stop_lines; - const auto & conflicting_area = intersection_lanelets_.value().conflicting_area(); + const auto & conflicting_area = intersection_lanelets.conflicting_area(); const auto path_lanelets_opt = util::generatePathLanelets( lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area, - conflicting_area, first_attention_area_opt, intersection_lanelets_.value().attention_area(), - closest_idx, planner_data_->vehicle_info_.vehicle_width_m); + conflicting_area, first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx, + planner_data_->vehicle_info_.vehicle_width_m); if (!path_lanelets_opt.has_value()) { - RCLCPP_DEBUG(logger_, "failed to generate PathLanelets"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"failed to generate PathLanelets"}; } const auto path_lanelets = path_lanelets_opt.value(); @@ -818,9 +890,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( if (stuck_detected && stuck_stop_line_idx_opt) { auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); - const double dist_stopline = motion_utils::calcSignedArcLength( - path->points, path->points.at(closest_idx).point.pose.position, - path->points.at(stuck_stop_line_idx).point.pose.position); + const double dist_stopline = + motion_utils::calcSignedArcLength(path->points, closest_idx, stuck_stop_line_idx); const bool approached_stop_line = (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); const bool is_stopped = planner_data_->isVehicleStopped(); @@ -843,14 +914,12 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } if (!first_attention_area_opt) { - RCLCPP_DEBUG(logger_, "attention area is empty"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"attention area is empty"}; } const auto first_attention_area = first_attention_area_opt.value(); if (!default_stop_line_idx_opt) { - RCLCPP_DEBUG(logger_, "default stop line is null"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"default stop line is null"}; } const auto default_stop_line_idx = default_stop_line_idx_opt.value(); @@ -879,25 +948,23 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // is_go_out_: previous RTC approval // activated_: current RTC approval is_permanent_go_ = true; - RCLCPP_DEBUG(logger_, "over the pass judge line. no plan needed."); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { - RCLCPP_DEBUG(logger_, "occlusion stop line is null"); - return IntersectionModule::Indecisive{}; + return IntersectionModule::Indecisive{"occlusion stop line is null"}; } const auto collision_stop_line_idx = is_over_default_stop_line ? closest_idx : default_stop_line_idx; const auto first_attention_stop_line_idx = first_attention_stop_line_idx_opt.value(); const auto occlusion_stop_line_idx = occlusion_peeking_stop_line_idx_opt.value(); - const auto & attention_lanelets = intersection_lanelets_.value().attention(); - const auto & adjacent_lanelets = intersection_lanelets_.value().adjacent(); - const auto & occlusion_attention_lanelets = intersection_lanelets_.value().occlusion_attention(); - const auto & occlusion_attention_area = intersection_lanelets_.value().occlusion_attention_area(); - debug_data_.attention_area = intersection_lanelets_.value().attention_area(); - debug_data_.adjacent_area = intersection_lanelets_.value().adjacent_area(); + const auto & attention_lanelets = intersection_lanelets.attention(); + const auto & adjacent_lanelets = intersection_lanelets.adjacent(); + const auto & occlusion_attention_lanelets = intersection_lanelets.occlusion_attention(); + const auto & occlusion_attention_area = intersection_lanelets.occlusion_attention_area(); + debug_data_.attention_area = intersection_lanelets.attention_area(); + debug_data_.adjacent_area = intersection_lanelets.adjacent_area(); // get intersection area const auto intersection_area = planner_param_.common.use_intersection_area @@ -909,16 +976,16 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } // calculate dynamic collision around detection area - const double time_delay = (is_go_out_ || is_prioritized) - ? 0.0 - : (planner_param_.collision_detection.state_transit_margin_time - - collision_state_machine_.getDuration()); + const double time_to_restart = (is_go_out_ || is_prioritized) + ? 0.0 + : (planner_param_.collision_detection.state_transit_margin_time - + collision_state_machine_.getDuration()); const auto target_objects = filterTargetObjects(attention_lanelets, adjacent_lanelets, intersection_area); const bool has_collision = checkCollision( *path, target_objects, path_lanelets, closest_idx, - std::min(occlusion_stop_line_idx, path->points.size() - 1), time_delay, + std::min(occlusion_stop_line_idx, path->points.size() - 1), time_to_restart, traffic_prioritized_level); collision_state_machine_.setStateWithMarginTime( has_collision ? StateMachine::State::STOP : StateMachine::State::GO, @@ -967,12 +1034,12 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( // check safety const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); - if ( - occlusion_stop_state_machine_.getState() == StateMachine::State::STOP || - ext_occlusion_requested) { - const double dist_default_stopline = motion_utils::calcSignedArcLength( - path->points, path->points.at(closest_idx).point.pose.position, - path->points.at(default_stop_line_idx).point.pose.position); + const bool is_occlusion_state = + (occlusion_stop_state_machine_.getState() == StateMachine::State::STOP || + ext_occlusion_requested); + if (is_occlusion_state) { + const double dist_default_stopline = + motion_utils::calcSignedArcLength(path->points, closest_idx, default_stop_line_idx); const bool approached_default_stop_line = (std::fabs(dist_default_stopline) < planner_param_.common.stop_overshoot_margin); const bool over_default_stop_line = (dist_default_stopline < 0.0); @@ -982,15 +1049,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( before_creep_state_machine_.setState(StateMachine::State::GO); } if (before_creep_state_machine_.getState() == StateMachine::State::GO) { - const double dist_first_attention_stopline = motion_utils::calcSignedArcLength( - path->points, path->points.at(closest_idx).point.pose.position, - path->points.at(first_attention_stop_line_idx).point.pose.position); + const double dist_first_attention_stopline = + motion_utils::calcSignedArcLength(path->points, closest_idx, first_attention_stop_line_idx); const bool approached_first_attention_stop_line = (std::fabs(dist_first_attention_stopline) < planner_param_.common.stop_overshoot_margin); const bool over_first_attention_stop_line = (dist_first_attention_stopline < 0.0); const bool is_stopped_at_first_attention = planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time); - if (planner_param_.occlusion.temporal_stop_before_attention_area) { + // In this case ego will temporarily stop before entering attention area + if (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) { if (over_first_attention_stop_line) { temporal_stop_before_attention_state_machine_.setState(StateMachine::State::GO); } @@ -999,8 +1066,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } } const bool temporal_stop_before_attention_required = - planner_param_.occlusion.temporal_stop_before_attention_area && + (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) && temporal_stop_before_attention_state_machine_.getState() == StateMachine::State::STOP; + if (!has_traffic_light_) { + return IntersectionModule::OccludedAbsenceTrafficLight{ + is_occlusion_cleared_with_margin, has_collision_with_margin, + temporal_stop_before_attention_required, closest_idx, + first_attention_stop_line_idx, occlusion_stop_line_idx}; + } if (has_collision_with_margin) { return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin, temporal_stop_before_attention_required, diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 139dd0f267871..2bf3df70e7a4a 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -116,11 +116,18 @@ class IntersectionModule : public SceneModuleInterface double ignore_parked_vehicle_speed_threshold; double stop_release_margin_time; bool temporal_stop_before_attention_area; - double peeking_offset_absence_tl; + struct AbsenceTrafficLight + { + double creep_velocity; + double maximum_peeking_distance; + } absence_traffic_light; } occlusion; }; - using Indecisive = std::monostate; + struct Indecisive + { + std::string error; + }; struct StuckStop { size_t closest_idx{0}; @@ -160,6 +167,15 @@ class IntersectionModule : public SceneModuleInterface size_t first_attention_stop_line_idx{0}; size_t occlusion_stop_line_idx{0}; }; + struct OccludedAbsenceTrafficLight + { + bool is_actually_occlusion_cleared{false}; + bool collision_detected{false}; + bool temporal_stop_before_attention_required{false}; + size_t closest_idx{0}; + size_t first_attention_area_stop_line_idx{0}; + size_t peeking_limit_line_idx{0}; + }; struct Safe { // NOTE: if RTC is disapproved status, default stop lines are still needed. @@ -175,14 +191,15 @@ class IntersectionModule : public SceneModuleInterface size_t occlusion_stop_line_idx{0}; }; using DecisionResult = std::variant< - Indecisive, // internal process error, or over the pass judge line - StuckStop, // detected stuck vehicle - NonOccludedCollisionStop, // detected collision while FOV is clear - FirstWaitBeforeOcclusion, // stop for a while before peeking to occlusion - PeekingTowardOcclusion, // peeking into occlusion while collision is not detected - OccludedCollisionStop, // occlusion and collision are both detected - Safe, // judge as safe - TrafficLightArrowSolidOn // only detect vehicles violating traffic rules + Indecisive, // internal process error, or over the pass judge line + StuckStop, // detected stuck vehicle + NonOccludedCollisionStop, // detected collision while FOV is clear + FirstWaitBeforeOcclusion, // stop for a while before peeking to occlusion + PeekingTowardOcclusion, // peeking into occlusion while collision is not detected + OccludedCollisionStop, // occlusion and collision are both detected + OccludedAbsenceTrafficLight, // occlusion is detected in the absence of traffic light + Safe, // judge as safe + TrafficLightArrowSolidOn // only detect vehicles violating traffic rules >; IntersectionModule( @@ -233,6 +250,7 @@ class IntersectionModule : public SceneModuleInterface StateMachine before_creep_state_machine_; //! for two phase stop StateMachine occlusion_stop_state_machine_; StateMachine temporal_stop_before_attention_state_machine_; + // NOTE: uuid_ is base member // for stuck vehicle detection diff --git a/planning/behavior_velocity_intersection_module/src/util_type.hpp b/planning/behavior_velocity_intersection_module/src/util_type.hpp index 7e5bff89485ed..5c188f4aebebf 100644 --- a/planning/behavior_velocity_intersection_module/src/util_type.hpp +++ b/planning/behavior_velocity_intersection_module/src/util_type.hpp @@ -51,6 +51,7 @@ struct DebugData std::optional> nearest_occlusion_projection{std::nullopt}; autoware_auto_perception_msgs::msg::PredictedObjects blocking_attention_objects; + std::optional absence_traffic_light_creep_wall{std::nullopt}; }; struct InterpolatedPathInfo From 8ce56fce9b40d99488b3ca74fdbddca8c66cca55 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Mon, 2 Oct 2023 16:36:15 +0900 Subject: [PATCH 3/8] refactor Signed-off-by: Mamoru Sobue --- .../README.md | 13 +- .../docs/occlusion-without-tl.drawio.svg | 571 ++++++++++++++++++ .../src/scene_intersection.cpp | 151 +++-- 3 files changed, 655 insertions(+), 80 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index e8a823a7e790e..98b8cce1cc4b4 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -104,6 +104,10 @@ The occlusion is detected as the common area of occlusion attention area(which i If the nearest occlusion cell value is below the threshold, occlusion is detected. It is expected that the occlusion gets cleared as the vehicle approaches the occlusion peeking stop line. +In there are no traffic lights associated with the lane, the ego vehicle will make a brief stop at the _default stop line_ and the position where the vehicle heading touches the attention area for the first time(which is denoted as _first attention stop line_). After stopping at the _first attention area stop line_ this module inserts `occlusion.absence_traffic_light.creep_velocity` velocity between ego and the position which is `occlusion.absence_traffic_light.maximum_peeking_distance` ahead of _first attention area stop line_ while occlusion is not cleared. If collision is detected, ego will instantly stop. Once the occlusion is cleared or ego passed `occlusion.absence_traffic_light.maximum_peeking_distance` this module does not detect collision and occlusion because ego vehicle is already inside the intersection. + +![occlusion_detection](./docs/occlusion-without-tl.drawio.svg) + ### Module Parameters | Parameter | Type | Description | @@ -115,7 +119,6 @@ If the nearest occlusion cell value is below the threshold, occlusion is detecte | `common.intersection_velocity` | double | [m/s] velocity profile for pass judge calculation | | `common.intersection_max_accel` | double | [m/s^2] acceleration profile for pass judge calculation | | `common.stop_overshoot_margin` | double | [m] margin for the overshoot from stopline | -| `common.path_interpolation_ds` | double | [m] path interpolation interval | | `stuck_vehicle.stuck_vehicle_detect_dist` | double | [m] length toward from the exit of intersection for stuck vehicle detection | | `stuck_vehicle.stuck_vehicle_vel_thr` | double | [m/s] velocity threshold for stuck vehicle detection | | `collision_detection.state_transit_margin_time` | double | [m] time margin to change state | @@ -128,7 +131,13 @@ If the nearest occlusion cell value is below the threshold, occlusion is detecte | `occlusion.peeking_offset` | double | [m] the offset of the front of the vehicle into the attention area for peeking to occlusion | | `occlusion.min_vehicle_brake_for_rss` | double | [m/s] assumed minimum brake of the vehicle running from behind the occlusion | | `occlusion.max_vehicle_velocity_for_rss` | double | [m/s] assumed maximum velocity of the vehicle running from behind the occlusion | -| `occlusion.denoise_kernel` | double | [m] the window size of morphology process for clearing noisy occlusion | + +#### For developers only + +| Parameter | Type | Description | +| ------------------------------ | ------ | ---------------------------------------------------------------------- | +| `common.path_interpolation_ds` | double | [m] path interpolation interval | +| `occlusion.denoise_kernel` | double | [m] the window size of morphology process for clearing noisy occlusion | ### How to turn parameters diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg new file mode 100644 index 0000000000000..086557f1a5bf4 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg @@ -0,0 +1,571 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + default stop +
+ line +
+
+
+
+
+
+
+
+ default stop... +
+
+ + + + + + + +
+
+
+ + T-shape junction w/o traffic light +
+
+ (Left-hand traffic) +
+
+
+
+
+ T-shape junction w/o traffic light... +
+
+ + + + + + +
+
+
+ + occlusion + +
+
+
+
+ occlusion +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + + first attention +
+ stop line +
+
+
+
+
+
+
+
+ first attentio... +
+
+ + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 430bb964d2b9e..84f0ed6c421a8 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -876,6 +876,25 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = intersection_stop_lines; + // utility functions + auto fromEgoDist = [&](const size_t index) { + return motion_utils::calcSignedArcLength(path->points, closest_idx, index); + }; + auto stoppedForDuration = + [&](const size_t pos, const double duration, StateMachine & state_machine) { + const double dist_stopline = fromEgoDist(pos); + const bool approached_dist_stopline = + (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); + const bool over_stopline = (dist_stopline < 0.0); + const bool is_stopped_duration = planner_data_->isVehicleStopped(duration); + if (over_stopline) { + state_machine.setState(StateMachine::State::GO); + } else if (is_stopped_duration && approached_dist_stopline) { + state_machine.setState(StateMachine::State::GO); + } + return state_machine.getState() == StateMachine::State::GO; + }; + const auto & conflicting_area = intersection_lanelets.conflicting_area(); const auto path_lanelets_opt = util::generatePathLanelets( lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area, @@ -890,22 +909,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( if (stuck_detected && stuck_stop_line_idx_opt) { auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); - const double dist_stopline = - motion_utils::calcSignedArcLength(path->points, closest_idx, stuck_stop_line_idx); - const bool approached_stop_line = - (std::fabs(dist_stopline) < planner_param_.common.stop_overshoot_margin); - const bool is_stopped = planner_data_->isVehicleStopped(); - if (is_stopped && approached_stop_line) { - stuck_private_area_timeout_.setStateWithMarginTime( - StateMachine::State::GO, logger_.get_child("stuck_private_area_timeout"), *clock_); - } - const bool timeout = - (is_private_area_ && stuck_private_area_timeout_.getState() == StateMachine::State::GO); + const bool stopped_at_stuck_line = stoppedForDuration( + stuck_stop_line_idx, planner_param_.stuck_vehicle.timeout_private_area, + stuck_private_area_timeout_); + const bool timeout = (is_private_area_ && stopped_at_stuck_line); if (!timeout) { if ( default_stop_line_idx_opt && - motion_utils::calcSignedArcLength(path->points, stuck_stop_line_idx, closest_idx) > - planner_param_.common.stop_overshoot_margin) { + fromEgoDist(stuck_stop_line_idx) < -planner_param_.common.stop_overshoot_margin) { stuck_stop_line_idx = default_stop_line_idx_opt.value(); } return IntersectionModule::StuckStop{ @@ -1037,75 +1048,59 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_occlusion_state = (occlusion_stop_state_machine_.getState() == StateMachine::State::STOP || ext_occlusion_requested); - if (is_occlusion_state) { - const double dist_default_stopline = - motion_utils::calcSignedArcLength(path->points, closest_idx, default_stop_line_idx); - const bool approached_default_stop_line = - (std::fabs(dist_default_stopline) < planner_param_.common.stop_overshoot_margin); - const bool over_default_stop_line = (dist_default_stopline < 0.0); - const bool is_stopped_at_default = - planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time); - if (over_default_stop_line) { - before_creep_state_machine_.setState(StateMachine::State::GO); - } - if (before_creep_state_machine_.getState() == StateMachine::State::GO) { - const double dist_first_attention_stopline = - motion_utils::calcSignedArcLength(path->points, closest_idx, first_attention_stop_line_idx); - const bool approached_first_attention_stop_line = - (std::fabs(dist_first_attention_stopline) < planner_param_.common.stop_overshoot_margin); - const bool over_first_attention_stop_line = (dist_first_attention_stopline < 0.0); - const bool is_stopped_at_first_attention = - planner_data_->isVehicleStopped(planner_param_.occlusion.before_creep_stop_time); - // In this case ego will temporarily stop before entering attention area - if (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) { - if (over_first_attention_stop_line) { - temporal_stop_before_attention_state_machine_.setState(StateMachine::State::GO); - } - if (is_stopped_at_first_attention && approached_first_attention_stop_line) { - temporal_stop_before_attention_state_machine_.setState(StateMachine::State::GO); - } - } - const bool temporal_stop_before_attention_required = - (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) && - temporal_stop_before_attention_state_machine_.getState() == StateMachine::State::STOP; - if (!has_traffic_light_) { - return IntersectionModule::OccludedAbsenceTrafficLight{ - is_occlusion_cleared_with_margin, has_collision_with_margin, - temporal_stop_before_attention_required, closest_idx, - first_attention_stop_line_idx, occlusion_stop_line_idx}; - } - if (has_collision_with_margin) { - return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin, - temporal_stop_before_attention_required, - closest_idx, - collision_stop_line_idx, - first_attention_stop_line_idx, - occlusion_stop_line_idx}; - } else { - return IntersectionModule::PeekingTowardOcclusion{is_occlusion_cleared_with_margin, - temporal_stop_before_attention_required, - closest_idx, - collision_stop_line_idx, - first_attention_stop_line_idx, - occlusion_stop_line_idx}; + // Safe + if (!is_occlusion_state && !has_collision_with_margin) { + return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + } + // Only collision + if (!is_occlusion_state && has_collision_with_margin) { + return IntersectionModule::NonOccludedCollisionStop{ + closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + } + // Occluded + const bool stopped_at_default_line = stoppedForDuration( + default_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, + before_creep_state_machine_); + if (stopped_at_default_line) { + // In this case ego will temporarily stop before entering attention area + const bool temporal_stop_before_attention_required = + (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) + ? !stoppedForDuration( + first_attention_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, + temporal_stop_before_attention_state_machine_) + : false; + if (!has_traffic_light_) { + if (fromEgoDist(first_attention_stop_line_idx) <= -peeking_offset) { + return IntersectionModule::Indecisive{ + "already passed maximum peeking line in the absence of traffic light"}; } + return IntersectionModule::OccludedAbsenceTrafficLight{ + is_occlusion_cleared_with_margin, has_collision_with_margin, + temporal_stop_before_attention_required, closest_idx, + first_attention_stop_line_idx, occlusion_stop_line_idx}; + } + if (has_collision_with_margin) { + return IntersectionModule::OccludedCollisionStop{is_occlusion_cleared_with_margin, + temporal_stop_before_attention_required, + closest_idx, + collision_stop_line_idx, + first_attention_stop_line_idx, + occlusion_stop_line_idx}; } else { - if (is_stopped_at_default && approached_default_stop_line) { - // start waiting at the first stop line - before_creep_state_machine_.setState(StateMachine::State::GO); - } - const auto occlusion_stop_line = planner_param_.occlusion.temporal_stop_before_attention_area - ? first_attention_stop_line_idx - : occlusion_stop_line_idx; - return IntersectionModule::FirstWaitBeforeOcclusion{ - is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx, occlusion_stop_line}; + return IntersectionModule::PeekingTowardOcclusion{is_occlusion_cleared_with_margin, + temporal_stop_before_attention_required, + closest_idx, + collision_stop_line_idx, + first_attention_stop_line_idx, + occlusion_stop_line_idx}; } - } else if (has_collision_with_margin) { - return IntersectionModule::NonOccludedCollisionStop{ - closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; + } else { + const auto occlusion_stop_line = planner_param_.occlusion.temporal_stop_before_attention_area + ? first_attention_stop_line_idx + : occlusion_stop_line_idx; + return IntersectionModule::FirstWaitBeforeOcclusion{ + is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx, occlusion_stop_line}; } - - return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; } bool IntersectionModule::checkStuckVehicle( From a7a02e10bdd021cfb54940c00563d217bd401578 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 3 Oct 2023 11:19:09 +0900 Subject: [PATCH 4/8] more refactor Signed-off-by: Mamoru Sobue --- .../package.xml | 4 -- .../src/scene_intersection.cpp | 48 ++++++++++++------- .../src/scene_intersection.hpp | 2 - .../src/util.cpp | 2 +- .../src/util.hpp | 8 ---- 5 files changed, 31 insertions(+), 33 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_intersection_module/package.xml index 2fd733f167546..0c9b3407d0f38 100644 --- a/planning/behavior_velocity_intersection_module/package.xml +++ b/planning/behavior_velocity_intersection_module/package.xml @@ -23,11 +23,9 @@ autoware_perception_msgs behavior_velocity_planner_common geometry_msgs - grid_map_core interpolation lanelet2_extension libopencv-dev - magic_enum motion_utils nav_msgs pluginlib @@ -41,8 +39,6 @@ vehicle_info_util visualization_msgs - grid_map_rviz_plugin - ament_lint_auto autoware_lint_common diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 84f0ed6c421a8..0f47fecc69453 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -17,7 +17,6 @@ #include "util.hpp" #include -#include #include #include #include @@ -832,6 +831,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( "Path has no interval on intersection lane " + std::to_string(lane_id_)}; } + // cache intesersection lane information because it is invariant const auto & current_pose = planner_data_->current_odometry->pose; const auto lanelets_on_path = planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); @@ -844,12 +844,15 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } auto & intersection_lanelets = intersection_lanelets_.value(); + // at the very first time of registration of this module, the path may not be conflicting with the + // attention area, so update() is called to update the internal data as well as traffic light info const auto traffic_prioritized_level = util::getTrafficPrioritizedLevel(assigned_lanelet, planner_data_->traffic_light_id_map); const bool is_prioritized = traffic_prioritized_level == util::TrafficPrioritizedLevel::FULLY_PRIORITIZED; intersection_lanelets.update(is_prioritized, interpolated_path_info); + // this is abnormal const auto & conflicting_lanelets = intersection_lanelets.conflicting(); const auto & first_conflicting_area_opt = intersection_lanelets.first_conflicting_area(); if (conflicting_lanelets.empty() || !first_conflicting_area_opt) { @@ -857,7 +860,11 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } const auto first_conflicting_area = first_conflicting_area_opt.value(); + // generate all stop line candidates + // see the doc for struct IntersectionStopLines const auto & first_attention_area_opt = intersection_lanelets.first_attention_area(); + /// even if the attention area is null, stuck vehicle stop line needs to be generated from + /// conflicting lanes const auto & dummy_first_attention_area = first_attention_area_opt ? first_attention_area_opt.value() : first_conflicting_area; const double peeking_offset = @@ -876,6 +883,17 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( first_attention_stop_line_idx_opt, occlusion_peeking_stop_line_idx_opt, pass_judge_line_idx] = intersection_stop_lines; + // see the doc for struct PathLanelets + const auto & conflicting_area = intersection_lanelets.conflicting_area(); + const auto path_lanelets_opt = util::generatePathLanelets( + lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area, + conflicting_area, first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx, + planner_data_->vehicle_info_.vehicle_width_m); + if (!path_lanelets_opt.has_value()) { + return IntersectionModule::Indecisive{"failed to generate PathLanelets"}; + } + const auto path_lanelets = path_lanelets_opt.value(); + // utility functions auto fromEgoDist = [&](const size_t index) { return motion_utils::calcSignedArcLength(path->points, closest_idx, index); @@ -895,18 +913,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( return state_machine.getState() == StateMachine::State::GO; }; - const auto & conflicting_area = intersection_lanelets.conflicting_area(); - const auto path_lanelets_opt = util::generatePathLanelets( - lanelets_on_path, interpolated_path_info, associative_ids_, first_conflicting_area, - conflicting_area, first_attention_area_opt, intersection_lanelets.attention_area(), closest_idx, - planner_data_->vehicle_info_.vehicle_width_m); - if (!path_lanelets_opt.has_value()) { - return IntersectionModule::Indecisive{"failed to generate PathLanelets"}; - } - const auto path_lanelets = path_lanelets_opt.value(); - + // stuck vehicle detection is viable even if attention area is empty + // so this needs to be checked before attention area validation const bool stuck_detected = checkStuckVehicle(planner_data_, path_lanelets); - if (stuck_detected && stuck_stop_line_idx_opt) { auto stuck_stop_line_idx = stuck_stop_line_idx_opt.value(); const bool stopped_at_stuck_line = stoppedForDuration( @@ -924,11 +933,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } } + // if attention area is empty, collision/occlusion detection is impossible if (!first_attention_area_opt) { return IntersectionModule::Indecisive{"attention area is empty"}; } const auto first_attention_area = first_attention_area_opt.value(); + // if attention area is not null but default stop line is not available, ego/backward-path has + // already passed the stop line if (!default_stop_line_idx_opt) { return IntersectionModule::Indecisive{"default stop line is null"}; } @@ -962,6 +974,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"}; } + // occlusion stop line is generated from the intersection of ego footprint along the path with the + // attention area, so if this is null, eog has already passed the interection if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { return IntersectionModule::Indecisive{"occlusion stop line is null"}; } @@ -986,7 +1000,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( debug_data_.intersection_area = toGeomPoly(intersection_area_2d); } - // calculate dynamic collision around detection area + // calculate dynamic collision around attention area const double time_to_restart = (is_go_out_ || is_prioritized) ? 0.0 : (planner_param_.collision_detection.state_transit_margin_time - @@ -1043,11 +1057,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( const bool is_occlusion_cleared_with_margin = (occlusion_stop_state_machine_.getState() == StateMachine::State::GO); - // check safety + // distinguish if ego detected occlusion or RTC detects occlusion const bool ext_occlusion_requested = (is_occlusion_cleared_with_margin && !occlusion_activated_); - const bool is_occlusion_state = - (occlusion_stop_state_machine_.getState() == StateMachine::State::STOP || - ext_occlusion_requested); + const bool is_occlusion_state = (!is_occlusion_cleared_with_margin || ext_occlusion_requested); // Safe if (!is_occlusion_state && !has_collision_with_margin) { return IntersectionModule::Safe{closest_idx, collision_stop_line_idx, occlusion_stop_line_idx}; @@ -1062,7 +1074,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( default_stop_line_idx, planner_param_.occlusion.before_creep_stop_time, before_creep_state_machine_); if (stopped_at_default_line) { - // In this case ego will temporarily stop before entering attention area + // in this case ego will temporarily stop before entering attention area const bool temporal_stop_before_attention_required = (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) ? !stoppedForDuration( diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp index 2bf3df70e7a4a..7bd923ed6198c 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp @@ -18,9 +18,7 @@ #include "util_type.hpp" #include -#include #include -#include #include #include diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp index 37dc83cbdf761..f381925b13208 100644 --- a/planning/behavior_velocity_intersection_module/src/util.cpp +++ b/planning/behavior_velocity_intersection_module/src/util.cpp @@ -16,10 +16,10 @@ #include "util_type.hpp" +#include #include #include #include -#include #include #include #include diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp index 7ba894bd9d32a..6acc1d60443bf 100644 --- a/planning/behavior_velocity_intersection_module/src/util.hpp +++ b/planning/behavior_velocity_intersection_module/src/util.hpp @@ -20,14 +20,6 @@ #include -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else -#include -#endif - #include #include #include From 4611220f30b1a00927e087dbede1c4bddd781c3b Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 3 Oct 2023 13:19:57 +0900 Subject: [PATCH 5/8] update docs Signed-off-by: Mamoru Sobue --- .../README.md | 54 ++ .../intersection-attention-ll-rr.drawio.svg | 134 ++- .../intersection-attention-lr-rl.drawio.svg | 832 ++++++++++++++---- .../docs/intersection-attention.drawio.svg | 190 ++-- .../docs/stuck-vehicle.drawio.svg | 42 +- 5 files changed, 959 insertions(+), 293 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 98b8cce1cc4b4..1dc358ab900b0 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -108,6 +108,60 @@ In there are no traffic lights associated with the lane, the ego vehicle will ma ![occlusion_detection](./docs/occlusion-without-tl.drawio.svg) +### Data Structure + +#### `IntersectionLanelets` + +```plantuml +@startuml +entity IntersectionLanelets { + * conflicting lanes/area + -- + * first conflicting area + The conflicting lane area which the path intersects first + -- + * attention lanes/area + -- + * first attention lane area + The attention lane area which the path intersects first + -- + * occlusion attention lanes/area + Part of attention lanes/area for occlusion detection + -- + * is_priortized: bool + If ego vehicle has priority in current traffic light context +} +@enduml +``` + +#### `IntersectionStopLines` + +Each stop lines are generated from interpolated path points to obtain precise positions. + +```plantuml +@startuml +entity IntersectionStopLines { + * closest_idx: size_t + closest path point index for ego vehicle + -- + * stuck_stop_line: size_t + stop line index on stuck vehicle detection + -- + * default_stop_line: size_t + If defined on the map, its index on the path. Otherwise generated before first_attention_stop_line + -- + * first_attention_stop_line + The index of the first path point which is inside the attention area + -- + * occlusion_peeking_stop_line + The index of the path point for the peeking limit position + -- + * pass_judge_line + The index of the path point which is before first_attention_stop_line/occlusion_peeking_stop_line by braking distance +} +@enduml +``` + ### Module Parameters | Parameter | Type | Description | diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg index d4d709eee6b99..51e926fe266d6 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention-ll-rr.drawio.svg @@ -8,12 +8,48 @@ width="3723px" height="2401px" viewBox="-0.5 -0.5 3723 2401" - content="<mxfile host="Electron" modified="2023-06-06T10:28:31.375Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="M_P_fA_OZlKNZHzEOQxb" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + content="<mxfile host="Electron" modified="2023-10-03T02:44:21.616Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="wkqIuFIE5UyEHdVd8sjR" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > + + + + + + + + + - + @@ -51,7 +87,7 @@ stroke-miterlimit="10" pointer-events="none" /> - + - + - + yield lane - - + + @@ -749,10 +785,10 @@ - - + + - + - attention area + attention lane - attention area + attention lane @@ -1141,12 +1177,12 @@
- attention area + attention lane
- attention area + attention lane @@ -1226,9 +1262,9 @@ stroke-miterlimit="10" pointer-events="none" /> - + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg index 2d590b9fd51ca..25a7c6b519f96 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention-lr-rl.drawio.svg @@ -5,10 +5,10 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="3729px" + width="3727px" height="2651px" - viewBox="-0.5 -0.5 3729 2651" - content="<mxfile host="Electron" modified="2023-06-06T10:27:24.636Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="EZYouzMJcjefpLDW8VVp" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + viewBox="-0.5 -0.5 3727 2651" + content="<mxfile host="Electron" modified="2023-10-03T03:32:56.314Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="aYRnTHIqVcSkLQHKGcXP" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">7X1Zd+O4te6vqbWSB3FhHh7LNaSTdHL6pNNDzksv2ZJd7nZZFVs13V9/QUmgSGCLBCkChFRS+txbliiQwt77w573C/rq/Ze/PM0/vPvHarF8eEHQ4ssL+voFIVhzTQti/lW++XX7phYUF2r73t3T/WJ36f6NH+//33L3Jtq9+/F+sXxuXLherR7W9x+ab96sHh+XN+vGe/Onp9Xn5mW3q4fmXT/M75beGz/ezB/su/Y3lO//cr9Yv9u+r4jcv//d8v7unb03Fnr7yfu5vXj3W57fzRerz7W36JsX9NXTarXe/uv9l1fLh3IT7c78/Oov7Ot/f1r8++Xiw9u3r17/5/++ezvbLva2z1eqn/a0fFwPXvpqsV5r+vXvr7/7/cenn8iVun6Jdl9Bn+YPH3c7tvut6692C59WHx8Xy3IR9IJefX53v17++GF+U3762bCOee/d+v2D+Qubf97ePzy8Wj2snszfj6tHc9FV4MPvfuSn5dN6+aVG0t2P+cty9X65fvpqLtl9OsOSid3z7xh0JpnevfN5T2sqLQXf1QhNBN+9O9/x2F11i/0umn/sNvLApn73+yO7/o1dfZZXv+jlzzPyz7cz1WtXcfeuPsyvlw9X85s/7jZfsxv8gtC3m5e55Hn9tPpjWfsEbV4lSVaP651gUr77u3bda6mvttf5pJs/3N89mj9vDOmWT1FpyQhlBXeoiRH2qakgYqpYtLSku9AynJYCc1cuMQbkMi0laTchS5J8OHJfqrNsfm2XRV37JagoCKWEC0q5VM7eIakLpgXH1JxNBDN/I3Xj65hSf1+pEoXi1SIU0eO3+Z9/XS2+sE/v7tnVT09//UP+Jq+/m+GAfS437d4c0t+XsvDD6vl+fb8qefN6tV6v3hvetBe83DHteuVIkTmLP5SLvf9yV6ovxfX8+f6mMEQz4vB48+bhwSgYy40ombdePt5t7owKJUi5P5IhTLX5P3PF8nGx/9ywKRWSmx2XUnCmS7l5urF6AyqEdISrLnRPq/V890PMLiBIkBdSX2+uXRl8uF+XJOYIlMVWFg6WReoyBmvwFpbIYm6NnbDCPv9gqWMxDIuogxyij86CPEwUtHnmEaQLQTySMFJI6RNFjICVME34BDTBKguiYFIKTZMqSkNyUrswDVVEN1VKOCvtpv3BX6NCk2TeTldU2X5iYY/5e7/8cr/+dbdo+e//bNCR7/56/WV3h80fX3d/9KPX8+rj080yADaWi4YF6JO1RjEOKBz2vaflg+HET01rEiLh7g4/rO7N76i4RsJHcAW0ln/sitvft1ukbrU564rWdQn3FjYH3t1y7S28YbhqV47gQdnNgzcfnz5V6nAihnxcvL0vf8kAVsuEg3pTOpSFtjh1cGXqM+cBHjJ0nH+tXfahvOB56C/a33fPots7jMuwqhdo3jzMn40qGY1NzY/51aJj+UcNOcs/99C5+WsYdm7JF3C8Z8L5/Rk0lPXNkq1CRSPC5/yH11e//gd9+P5h9u6nf62fXl2/1yFG6DF6lRaSvhRhelV57VyE6FWj+QU0w439nwmphadXMQKpurrQLYwVqlf9RD69EnKxwneM/8F/ffcPfv9LbKI48ACptjVy6SBVdzSSSEEKjypCqwIpjzBUGXEBbEOJizahD6XNtfjw8Ne//fr9gq1m969/+dvf/ke+ntFe/rczI46ihg4MII6E/KLmbRGNOOBvCrASW9W/5nlJe29mJueXUYopdTyeQlnC9T2zSpwknv9UOP66kVQ06Gbm0emoehlIwmNt2XPmHabIeLwjsHCeKibvsJ3zMCrvBNig3wbvCIydaIER3oG6slmNEzf2gIWDYuPxDrdqngeZUXmnnzkYwjuL+fO7yt3hqRFXb8v/nTCLCQtGe0AxVpUczGT+eoJEM8LgLQ5Q+L8V/AAAnA4mLSci3dnj38ycPQVPACFU9+If0KXUAI2SH37cfXf1tH63uls9zh/e7N+9Wj5cb9aygVEPaXZM2jSFzocrBXWCKuFcyZXyViPOauNxpf/oVKD+T+h86Wg+Bp1RAWx8jGl9tfkfYEA7WSvbF3h22hWSmdySeqSQyE9dwQijggOxP0kKV2MazU0V2RNymuRCru8qG3KNb6Scu6LpZo0JwZx1eugi2O537QxxUljGUzN/WqkfPs2//vL67tWbf77+L/55NrsLSmyZKuNMe3ajpr4n3ihZBec+zY08FYhiTcx/ihrMHEGEwB0cO5HWgbzr+Y1agFBGKGN8AQpTO627wcvbX2RfGPCt83KnY20v7t7eZZVK17G18+cP2wT+2/svJTncvUZIzWFHO0JcIuCgud28otCgCjwWTHDGuWRG4xKOQaELjAnT+5cnH5QUChGshGQEY+s2beZdwpeMT8sA7WAcWu5OKv/8QZpDZKySl6ORUdACE405wpxhbMzAEyZjiGsiLhlJLdc8rTRiVvAy+1RxZUSTYHwadISUPz65OIrNKwc6NvUwgQusSHXoYT+vMiMysl4m8okoIPZTJArNKiUOs6Y7njsqHvIJxWShgYjzGHVVsFBNC46L5e3848M6A5HCTh4/14Wge5kCEsgzkikekDVgyztuH5ZfdhbyVb8kPfvbZUGQpsj8Os4VplpsV7JFVIVGRgM0SgORGgkt5fZja3VjA1bY6BTcCICBVKV4fypnYmCbH1FogvavJixL8+lAxz9mfVeOnaMcABPHZXxWnq4omfLjZYm2+RHqGfZt7uF6NmnbdZnweZk2pbwwlCTDeHuThOWuVqk0ifg5RJe88HOdn9v853V+brsuH36WmhVaO8XRwhxKBZPMMYcGMDi4vDSMXyA3lyQyo/eLy0dO1d8xOhrC6DgVo7fmzNY5vfXCjFidMJcP8fB8BIldrkZuHDkyRweEAC4c3Q3dQGFL23UZ8TPChRAetnJVSLpXmIdn7IHrm6OBFEgkZfR+qeBDGL2qbTkTHaWtPqhT586N0UtudphQ0sHALb0sGklQWuDul56ehp9PELhtuXAnctsLs+FoQWSzWHAmmB4O1IS4q3GWuHI7wC0yUTqCkW7i7o4mxijZ96vZfty76Y0cvekNbDIGJCqcVdMbKFmM+zC386N35oO1M2y4m9w2qbGVw7KgAPmT9LqB+STAlRMlh29asugmWQjppAsRAF3GaKwCkyVyBTBEllCqGFFf3C/38aaDXRVHItYMO3U5pRD5qWFUp+xHdGzRzqTuz56k6vZj5uW1oY6uTstS/drJTR1DNFRpcssiMWlfN7L6FJAJMFrfmx782NH3ppXTcmGgnoQObv4hm+t28OVINSDur5HjFnLABA1QP9NFiEbzpLQyb3cYJy8fSU9uDA++O8LDJkVJOn5LiDOvepDcDS9Lmzw4xB/sriarfuapOGD8xg7nzQGSUrcQXjA0mAOU9FaLV/cCc0BA5dNZN7lyPX3SOjcbTa6Uz1MjNbmCqRK52jN7qrgFT5wDVKFAPmtMqrD4mtu5xRlaubuz9aG9MBv4h+IM2CmoOyrOwISzWuyUh5zjDBob7Vghaf6rWmrtVSXJap8S3+ll3i2Eqi6QzOcL5xLhxHjG61k4QfE+1DX9KFcy643kVLNCiP32OmlrmKNCyupjAOEp11X3vAbdYvmWQxB+utCQVFRxKRhnBFHMvNAQkQaemJJUUy41d0NDRokJ4xwDmFOzDka8YIghqhHlCrttiDBiBUfafoyVP2eDmxUUoLZxJMsgWST+CYDT0QW9bD8yMblmjlXEGa6ajzbiELTqXzq2PMPJ2Md6OEaPRUyjrrWSuTuhD9DXWi/MRF/jXNRVBNXkUYx1ocj++BmYk82beohzE9b4kGsHeGLXIgS4d6aIg1hZKAjiDXnASrdLhPnjh+XTvdmYcizWUVIyKBoTLDNWk+iUGZaXi4sr3cLOVNJRZIa23YSR1puMFPrhrPUZFPQMh34P421rcXDTosaYSL9+RnnGmIZlBluhxjGEOjSclZlQU9LGn4KPItSyXQbEAJkezctBoovDuSW8twYLuh13uSUIS2pJvo+0KLSvpBvUs8yL3UArjsfarz6++enD5zezd/zV77/98OXHN7/83xU4E1hUfQ8aLC7++3FlP5g9b2rqX5oLKP/wZcMq9nPzr7vd/79Z6Nq+8bl8ekP9p/ntrREPgh42lCKvSgpt/7n9hrnu2lvlKeAd+8afvl/ermfv5o+L/f3+3La6eW/7e5tvP3+YPwbtAQrdg8MPf+Cxto9g33ZAx5jX6ybM2MmvD2YDAF/S+/vFYtNj9mlpnn7nTC0lfafumFX51Qv+ulzp43q1/YVAKHan3aedAE2JW1tFENAYCAIC7AZZh7gIQAGKPDwR9Nj0jLQt7p+WN7vvfl4+r6NSiTO/SyfgXsPVbNsI0TeQUOP3gu+3idmcZRCF3F0PP8eY1s5qspoIPXrHZf9m5tHHzbkDeadfD/Dz5h1XD2K2A9Eg3nFXw4H5K4N4x3v0kW1pkHd65mueMfMwrLxsmSOAh2svphsPeLjHPEmAJ6hr6yXBrkYoRbRDKMzo8AkmwHrCtl9NZKIFdXv9RgDEO/7ZUHfTRqbd1bDb3XpMAPEfXY09wQTmnxE67VwmmPTiSqUHJ3VRzb3VVDSu9B9d7HJVez2h86VIfBzQX2eU6aDt9bT1aaGTGtq4Vqy5p4SQlQldd4pIVUCTdkeaiQHTK7Jr5NTohbgsvPRPIXQBJB9SmZpYl0qOnqgviY+Cg5vgsDJzwV0tsZp5ApUciQUWe21cKFBGwAA2i+nITBCc799nLu9oZKs+UY9Gtl6YD/Zo7sYO8RF2kEbualVcJRH2kH7O+QtLd6hc3SzNc2NpJXihtdvhtubEYaM0wO24j8Scx+yECxKD9nPyXXo+t4diO5k/N943WoUX1XKHlvYYgerZ9BKraHnDMEP381heCh07VPJuOM8tX4pR5vR2FszW4AwAbaLd1Th1VovM0iGDTC72ccM+5i7NpBvb7cEB3mrmpI7W7QTmgIuHpHeugFuGL8jwQJxf1F9V7abigIuHxPOQeDIO9HdM7iHhAebkt0Yoz/GMfa8zo4DXOSqh+iVWXRTFDobvNn1UZocEpCgOH5EAKIqMpzXmRXzv7LnVirQett0snZvtw6mbmLaNyg6vFWFYe7oPtGJk1lYBaL1t9uLHZI882wb0f2ES8VrTeOm1hBKsYG1N5zkGuCRGl3lws0NaQZx9l/mybCOsNUWQOtXO1cH6FGv612jKTvMwrwT426ZqaZ6SMJh2UoZaIozdyhwmzAS95sMbNx3oNp+SYjOnLxchfoC9au+ShGRyhGzJJknLWkE7gtgPQFKPWHW6jlUK3yhr3/fPkEg1NMNSYvr2z+jJG52KH1Qk34p6mSh+xBmKhd1mLcG98J3m0fGavsACEJBmGbvpCwXE5qAoFBKTpjiUJ3SXQJi/vE4w+74ytNlXhoj+ctHVHyaVlOTlFhZN3pYDZQRjR9hcx/JIKdJuH3fpSFyENGc5Tc+xEJGryYdw5IMMkI+xXGepJCmvGQOOJBl7dyRRSnze6ACFKx+vAifSGzO86eDW4khgWhTc54PSlUBw9T0XwUbTaGnAgX72noRZAk9Cxck9Ztg5LW3t39P5EkKGeoxtskKhs+mJ04wkEO2TJtrgOpgyAQkIk80THN2XMECYOC+a4iRY4RONQh1koxHNJj3lq81NExtqpXmnzmZFoVNnsxdmorMR5OC920k6eNwZby5EcFqlTcUfAZ+asxseslz4PDSlmeaV0+zyOUUD+Vw46yS2TVRAMD8HX9gxmSul/4w32Zww0sHosP9siMcrAubnVa5FmAPVQ/3CxJl/QV2Lf6yhlti5D0ng9dIBRmqcSFkpW7ULt69W+Zw0k6866fepIMrP5MMI6YJTn6lj1pDrEZSCIWf3BAG1fgTuxDbL/Z3YpvPCNrAM3vDYMIAzqwmvEqpqvJvKHTmBlX2SQISZSyqhAO/VJEA0Wfv6XoHLfpAzzjT642AqVAXTeZndJbAIh1slYkfAFPZW09FgCp7QEKAvTTR4z+gjuED74VsOSiitCq2r2VvExwzJeP37GEIPhgulmLvIMUhy9d3vj+z6N3b1WV79opc/z8g/99vSf5fbqXb0NuMCU7PRikpzAAssEF3OgNCTu5UkyVaCMy1C+qAec7CKV+rNplyusx1UdWXneLNWnugxjA4VtJl+TAUt7O+vkUsZskKNn2LNKwxpLzrhvEL+wo0GkqCphBArzJg/lHASXmgMJiTOCHdnMCGx9TpTDyYM6UE6tvAeqqhLTTLKlU8jv8VehZxpJhMGSO5onslqx3uMZsPaGc2m06UIdTki2/iic4iTxczOIU5WZjJRgo00NVQB27bduiU3M8g8tay3k5K23wU17xLJhVmOBm55CqzBp4g7Ui0AQY+0SfuLaYrYb9dIteOEkZymMBrOazJokz9Fu5SECiNjrXfBg2RxLIHAxw7VyEQa7Em3l4iyAdOA8NnYohE6QdQeaJmIBia6wbROy1xJ0BjnFHZEw7kLbT8NxxMNkMQB7kubEQv4fKdPkhWcuRXQUu24o64xC15wQGnGiBSIGoXR/KeodHvyj+bc6dUlBPe2aa7nN2oBOvAJZYwvgkjVyh/BJgxpIj/QcHpLC2RfFhMa8o2LMaqdwV8UchZUfoIOMsyfPxhuNX/c3n8pSQdNqfNIghCXCIjC3G5eCUnlzpmxx2Q9g5EUChl9XkhmDnGFAP/ogUvG94+GDDeKSrgrpDlEuC0fT0c46nsIcqJbSMvRUehmSPH27cFIJtkRKTOpU0DheEbECzElowqd2LwyoJvtLHYadOvVDeCkFQ6bg2eVdubRhcnCRokhI2L8zQ8ImEYUmsXydv6xmqs8qcg0A7KZi0xASpkNL90+LL/svAVX/Txp9rfLgiBNkfl13Bh9VIvtSjaZo9CICV56E6VGQku5/dh6FjAuMGYYc2OxGIhUivemYiYmuBPwUE6eTqiN7cZNsLNOZCsaHGlTjeMGhnofHt+9m4V+U4nt/sJNlpYRYO+7y7uV+crD3IBB+5DxF43B38ecBw9liPZqfvPH3eZrDRWsfEFHQ/nafFJPW+I+TlXzE5LO/BbIG1BGrTO/XohHATfCGDVdMGPFTy8LpUp13ZASgKZjFEar0HyxVgnMBNbM82DlDkyrzsP+aWBCeGMqmHBOwtgYB/mwxsc4eYsQhHFf75cPi1NAOfkWoZNCOc19f2lilIvfm7eiio9EHXSqvjkE98ZGudx66grsj0uQDi71QDkGTECONh4K3GECeRn7odx8vTbULs0rD60mhKU93GQJSxi5QxcQBWApVhcEmBdCPJdRRoUFwFL1zQxgyQpNPrBEvHkQemj/rzLGaCfA7GOMLtPFhiXIn9etTO0iEwcVsQqPblaPtw/3N+v7x7sdaj3DsHVA8XKkwsj9uikHYGMPAGLmu8zeG8OZZbqCl/L7/n6xeDjkN2tK2wGYtDcPlK+YoEeaPuWytgOK5UDNoaOBXkCoOuuMACa8GZMc2NWpMwJIgM6bp4e+4pDzyQmgk8eWYyUF9CfWaWUFBA20PMmsgKMpl3daQNDgxtNNCziaenkHy2hAfPk08wL6E+6kEgNCOnSei9qRX2ZASMfLU8wMGCA0p5QaENIO8xxSA0he7uXzyA2go6XYzyayqCUSXiModMiG87khlUVNs0qyP0Ssdh4J9x65NjXQD2dim/qkEu0jk8s97vxa+4yOOza5N6SPTZ2WcjRvyp1ern1a8lW5uZnSL5lTZAyzOjLp3NGmmZMuq4z7yKRRTrDe/tYJTWsW4NjIxbSOLThNT2LugvON5N3TvBLvsZMhgR2zLLi63c20sCVjicxrFuCbAWY67To++bSLXrAulJuaUmXyBhnTOIkxzQK8FgmPs0PUameJbsT82pSpfKxnFuDMGE2TR0jNa1loQ03oWESqunU0Ay0868A0m9z90cuIjkw7eUqk49P7P/oY0LHFTp0S6SZPB+llQKclnT/vPCfKBbg+zkDhsJ/6uTmpDWY+bQpHP4M5raDkDXEBjo5zsJdZXhWdvKnBDG5a2r5MZGOZB8eik9vFTBsBYkghaf4z/OSOPsZcFEhWBpmPn5IBxC9b+BHO9O6lRhBKcAqFCNA74oxyGW2UbTvDhAemqS423omtg0KophcfM1aoPUE09/MIyoaIEjC3x2hwDRMvQPXIqzW9JJIyJammXOqgPvUQAwFt6qfnH6drPXWOZoxUCQNaIC0YNpzkK7Wxu9bDPNQr/DMSAFCRIwIYniycsCs3Uo8A80ORwtqTSSRdhjhlppmreeSoJgMUiL1odsHXL/p2we/JE51TnCyydk5xsudnJsoeNoprTRdhTs8ExeqqCBpa8I6Fc5fGTWj7TWKPow3wgeUwjnbo2Iaa2IiG2JDeQjNoBEQEEaJ5iRBvY27GHe4eJkGUtd2EuyIUJEG9B0AMeIao821ViA/0tAamDzwbh4yDCBdMepqCSXUbvwo8imCydqEQQwRzNCdIcIV7eieIFE7Sm9CAqxib/avZ0Np69tsSBeQImQIge4N9wcDtPMoMOVRhFL7L7gamya6A92z64v8gUrQTvNsinCSfAnxosK+TeyiOmE/xcmA+RRKyVAkVBROccS6ZoEI4FSW6wJjUQCaXoAhM3snjvp3ZFikpK2iBicYcYc6wATt1wpQNcM5OnIyRVGaNfsbNtmPFlRFg4kyHPi3STl+LHkEhOSyUhTn2rGqBKWpqehxW19IkCMDkyb1YPSXxMC242oudaIYnuS4EJZV2A7SNzknsvpFqdp5XNTtjhZZ7YHamMUteaFppx8imoPSfNefchPa5S2zDO8DqySlV35yjbnNbRvxamqmscXCPRYCdE9htoFfOVUXbU7PP4V3slc6RSjMZTJyKKXo0p2yeb9nVR4TkbGRqzyckI7aOppNI3g7JocjPiE9ITnFS1Jy2IHeg4Z5SOOUpUTPAGDyhE/GgutICpdOn7IsAyy03izwpiU4ojV8EpGKfhRW+o0ImVrhbRDp4qHtHPUBkU1r0MKXzbCrHsZMUYCQCSAafuqmcDLCnM23rInoDaP5N5eTkcb5oTeX6k+ukmsrJZAZ78qZyR1Mu76ZyMplZPk1TuaPJl3mDJTm5IR6tqVx/0p1WUzk5vdWdjjQZNpWTuRvcCQWHnJTgfCPWtcjMuj6TpnJgneBlnvtJzXNnWDiQJahVZSebdAzW5lzmOJ72HEeG3ZnaEilfeUk7x9E+wGVcezuIaSHpS9GDj6YGMU0mB7HDw2gvM7Jj8oJqxhwMzGCAF6DeKfF4IcS5cFyxaaiaUV03ZCK2P3+7HyE7Z2TLvDT1DbQ4PZYEZQOjYWXlomu+C8Yd6y6y0q5C8tWPY8XqsDjpce1WNciHFYnb7ksoMdB0NKtx4ahjQrizw2KzYojf6DhWrBjqtFkxr9p4wzwUu8yjrRdwACsqjxWljsaK7/+1mv/l+sf//P038Xlx/28m5Pp5FpwPfpzeMiQDgLrOeKGQLLTWtvkX1OSPFVRU3cEYoOpILAqh9q0HYnX8CmnwfUzHL/FKvbl62/Txjtvxr5VfghVTrnQhmmc/pbxgfi4HUYUAfMLRun2F9PHOq69fUCs/iDFmmI7azG8c1sCUFqhWjuTIO0as4Ggv7coPKUzSyy+kifjYkr3LjcyMgJRKh2K84D4qQydyPKmOb3FWBGrqVsynRU7tjNpI3tnNyFK1s5uRvTATjU1xB1OEqmMK0o4NGqq7aac826BT67qR2/EFBaKP6MB3gON7Na4sjMLV5GisO1na/OX10xvFLDlKGlhezhqBmjAsuGgy4zAeN8sWiKFyvrOxkBF3lDhujl5p5AtrJs3/m5bfA5pKjdZ+8gjmr7WRVA12xap/99XBzSw7GlC2icKp4X3Js5ILxZUxBZUUCuBZSYQoe+BoIgf6M6njzMQMDUH/vq0kuVNvbsxX6LZjdY8kX1/+9Zf//u/q7e+/PTD0Cf/xP8vvQH9BIwzoh3fKD2bPGyl5aS6g/MMXMOjjRas/l7/F8ODT/PbWqGgEPWz4hbwq/7m8XbeFrq+fAt6xb/zpX+XCs3fzx8X+fn/uFRnfvv38Yf4YtAcodA8OP/2Bx9o+QnDA3gbiN/vZEoZ/Wpqn3zlvShjZ8apZlV+94K/LlT6uV9tf2CsTwMejsQJinCHHuyaJPQvrcXdoMARmI9gnoACN3TpgSCCzSmk/IpDpZXDEIyQrm107EQCuKUBKBZCSqFikJBdS9iWlcAvjDCEZUN6QlpABFQwTOcGFoKIglBIuKOVSuXuHZcG04JhioQmUc6sbX8cUSrpVolC8WoSOkXULbnOAZ2Y6f6sg5fZIc2YYdQpTz/mKERWSI6mlFJxp1xMrpO/Iq2Su6YkFjYyF1NcIMCF8lmvl4HDXncsXjmopUQFU9ykgoIKljsQvvaob+vtZQfIAIZQJqGMMeNo88AjWBdA3jpBCAv2kxsjnAX9JgJ9pdJJAru8JaIJJKTJNoigNSIneX5eEJgG1DMe4Pw5kEozk7e5Hrbpnrg0yMvFGSPjwrTC2GOh/EK3rEu4tPJ47Dtz1lN64HuzY4fdqY7RMGKg3oYMraEjrytTnzZF8WO2/aH/fqE6sgNSMOOlXIJcOC/f14+e6H7ftYM+E7/uzZ/CAVd4uUjQ1duJeHUTiqlTVtZ0q1Wj+AM0dH50hDJDnQSElVxe6hbOO89JFzvFw8AFSa928rnQ0kQIXxKEKJ2XoxCMMVbwAk+yKNqE/jjS93G5nRhpFaaFdVygnrLC70nSiweMzYxInpBlIm/bnx1j77WYmB9gMS0pdT6dgZNihVeKk05hsJqoh1yNraNDNzKPj+GoZDnAQfrPMU5WHjsE8rBr9kYJ56K7NcFzm6Vfec8bMI9xGl6X4DsxzM6tx4qxmkMfBsfGYhxPpPTpJwDzH5s/5zLOYP7+rHB5+t6q35f9OmMeErRKrQQorBo6DhNbjTETLoYR54Fg/6hkBiA/h7jq9AKTZNjLq6ePdrDx9il3uYlwMCfCCdnmVGqBR8sOPu++untbvVnerx/nDm/27V8uH681aNih6KO2maQ6dD1ey4VWgXLnV8pxxZ7XxuNJ/dKxV/yd0vhSJjyMXrlXDoV0rGqjXP9Dq0a6QzO6W1KMFB7pyYoSNyQ3VsJGqBm78LKTIDsTTpJeb+pcRvUJ6FF90zbpu6OWMMTfnpIc6grW/Whjwj4WwluA5uPzLlhVzkdjl7xOAeLLJGNDJM6bLnwZQ5cioYAWEWRUO9iN1ZwqG1R86Q472wnyARinXeEB4uNdNUW81NwcoMtDQft74C0t3qFidLG0vzIelpWaFdiNGxgDnBZP7oZSDeRxcXiBUDjNOG0e3UeM8kjoG1KgOLe8bG75JKHyT7HjdTl/d58fz4W4rid04q9d0KjZLx+9Y9m2wNNC8oPXCjFga4UK4jfi41qKQtUHNg9vyweubcwEVyOlqFZvXJ2uJdl6qCg5VVXBuqkrJ0A6fczkYvqXnchXInQIWm6X7BZQu8N3hLunWvrPTSIhsppfOOKXDI/GEeKuptDFSGhDjmqhSUhKblbB3K1FkjJN9YeML18cUVh0p01RH0oC4y1mVR0KBBe7DHNzlzGewdobtMXZZN9iIyoIC5J+uKpJNFe+Zliy6SRZCOulCBECXaFV4ttdoSrKEUsWI+uJ+uY/WHWy9MRKxNkXOrhD5DT8ZAg7feAQivdSx3oVpcT2hPWnVqVSxvNR/6mjrtIz01I5uOrDHsptHi0n7upH1JxbgkB+tUrIHQw6qlFR5cVBPSgcXjMnmuh2MOVLOkPtrdg8RNfGHxfeg92HJuGWRO+bttClZXi7BntwYXA7MHOFh08Lk+Ln8Z54iI7kba+YaDeMFaDWBkEzLAZeE/N4VQ27lhJfW1Cd3QfqrJeaAAO/pN1UXbV4vPAvKdiJOlSTFAhyA50wVph2qUA1RhSSmSlYNLU430sCCtcK8bB8w0kD44LlEUKQhcTyY5xg8O8F4sD1Gu1laZsbSklqS749ArPbZZkNSv73qUnDF2KwNnaExe2iX08LBJtpP23+O1UX7++XtpYn2i/Nqom2k0MvuZEAfGAlAQbwm2jxA4Rk72NK3giJoDlO8Xudc2D2phyqrHsGpVFMREK38NqqqQRINzrxm2h0qz7WKVb8K3EyQBKWoNoB7YR7DPK4yVKXLDWIeZzWmA907g5jHfXSiZQLmIRfm2VEAK9ecOwZ5uDuXNSbycI950iDP+H3Mztv/zBRxXGNMKzy8IYy/HmfcAbzIdpqtAL8ACMPe+W8hfBiAOKsxb4b2mADiP7pI0hBGjFC+c2kI04sr5dAA+AxTP+IiSTSu9B+dCdH/CZ0vReLjCYY+9BvDkdbUxlQUXoc9jsxh5xvcVPLKtk7VYERMEDnNmV5ImM32oqlIFtgP3ZWzkKCBKlHp1a9x2EXXZJL4QDi4UowRjzlY4j4NIrI7c4yoemKZxV4AUgKB9tRt4WU/b+YlKtmhUnSPpchrLkXpzeJODJHpI0whjdyIZBVdSYQ9tsT2wtJHsnRooF3kFmhnShglVbvdYGp+HDJKs5iO+3CtafKuMVZlzyPn/XS53wZkO7nfXpgN9xvFws+0HN5W1jPsBSKJWTp+069vIhlQhLK0yI2lGbWlPHvtefj0CEa0t5pMax/J8T3x524hc5dm3A3w9uAAfzWtWVoOuFQE9U4YcF2UTAzOnGTVkPbaaok5IKPRw7n4SDwZt9WKjWIEqMg+po/kBAp3pnZmMQuokzqzRhhYcVEU9wzfqSjK7Cx/X1EkwydFAYoi0Wn7U8kAR/rFmRXA0qH+WZmbf5ZTLzuNI35M1QizU1c6Vow9Yz0g9LBtveYHZo882wZ0Y2PSbNG+tZr0tEdECtbWmo3bCPskvdhsR69vuhdbWb4R1l8qSJ1q5+pgfYo1/Wt08n5sdnBdjo2/UhLGCGUXZaiCVNxYRUIqwBE6epFQcKe8Az3ZUlKsynLeUYwQv7CLQIVd8Ug2eguismbwx21BHfW1NuoRq2Vc1VDdbN9dy2qCm0UKiVRDMySb6VktuqH544fl073Z6uXTQb2vlTc6FT8LnZ2Kn0W9TBQ/4vSOxkNj8tRpsOSuE1vLC/Bzxm4QRwGxOSgKhcSkKQ7lCd0lEOYvl5P3ckEob8qF6C8XgzraRZCSvNzCosnbQyMCGDvCRuLUjrm9zhIUjalj+07FE7mafAhHPsgA+RjLdZZKkmjOkoTdpK3BopT6vAlw1ufjVeBEeqNQMGnv8c7tXD/XkUBw9S0Xv8bTZwNc7GfvR5il8CPIA1x22Fx1WAkD+cWpPQkTdLWAAmfTE6cZRyBAj7W0zd11gPN1sp7743sS+gsTN3jalCeuqnfqHiAoGi1JwWMR7tgOEtH1uWmiQ61079TarDh0am32wky0NoIczBcD1TbCmwuZQyGp2mabIqRPW47G2Q0fWSZ8bg/kbuskrxRQl8+p2705lM+dyYA0sXWiMxiX0Mc0HwTlRTlo1PGgkQ5Ghz1og3xeo2O+yqs3KmEOVA/1DBNnzDENLNTqPfrBmTtLSQK/lw4IvMSJlZWyVbtw+2qVz0lz+aqTfp8MYq2VuuGIkC44ME0uZh25HqHfyJCze4KQWj8Cd2MbC9VnWVbYBpbCVy7FAalOwquFwolL4XXkNO+zASLMXFJxAuTCTAJE8Xt3jxG67Ac54wxtOw6mQrMydW5ZmUx4PTaUOgKmsLuapolhKt9BuEIJXCDEENWIcuXulKSi0FrbTwEfnWS8/n0MoQfDhVLMXWR8JAnwiB/Y5nayHb3PuMDU7LSi0pzAwpySdDkDok/uXpLp9hKjyE5s8Uq92ZTMdfaFqq4cNj224opw/zRCBW3mIFNBC7sBNYIpQ1io/1OsyAJGAR7q6UKEkr9wo4KkfKsRCCQqjBnKuW55cAMvGKpJXHPaGUas4KiGkMrjkrIAQAEJ6mVXMdenPCKrkPQCfKiyLjnRKFc+lfxyR5tAl0h4Uzooqy0PL6YrsG7m0mGdLldokD/SMkanMlwBZ6c2XMlNJuqwkaiGTmAblVsHJdeQgtbbXUnb74Kad4nkzMS89SmwBp8iqqvTAEe30B5pnvYX1RRh4GaQbXyBJCcqkIb7mkza5FHRLimhAslY613wIHkcTyiObbCRiUTYE28vFWVHpgHRtPHFIzSAVp1smYhHOUm9zrjOpEFJ0BjnFXbEw7kLbT8VY4sHhsSjmjIGzCo7PJVsN+PtppKN/YUbl/Ptrf/d5V05w+1hboSufXbai8Y8s4O2Ae62DR5KW/NqfvPH3eZrNVF+u3lBQl6+Np/UfbDc961XNfRJR5kJ5I8CsEJZzyykgAkRLbOwOgciaiOhZKmuG5LQ0MR1Pr73u5LBTGCxnCep3KnryE0O7jN1HXk9j5PDHBS5GR/m5C1CEMx9vV8+LE4B6ORbhE4K6KTynVipgQ7y5ffjrfl6bTardEx5PDIhM+yJnCUzVPbuPvQmAGZImk+PSUAsIk6jHt6DUEPOwdFPvbxSS8vh4F5nQYUHd9cRHLslXZymbRqFCRSC6T7F0OYVMH74ZvV4+3B/s75/vNsB13OvsciOXPjzh0PHBNs5xTeGN0tD9/CkYggmm/J2ACntzQMlLCbuWYzZJwnYkXL1ghQCyIqbTDAe7rHhAe3oLZs0JQVDCknzn5Fyr9JSswJJjnYvP/QimfC3svQOEF71fFexOjZhHjm6fVy3l+HFWHuWCWd+qgtN8OY/RaVwpn9ixgq1J4m24c+6VHBdSEAhiBdJ4xAGO+TLKwwuiaRMSaoplzooJg6xEBASz4CDnAg5xW7sVZVQoI2hIRg2vOT3DZomQs7JBCBARZYoYNiycHJEOSsh3Jd2pQo7lyGRtB87Xjfb9FADFog1zAWsdavBcERbp4orus0Ii6/d0Qd7kGZicGCM61oJc1wbqqGUIDmwe61RF5t3adyEtt8ktn3CAwLWOZTBDc0TqYmO09mmt+AMyjmJI0YkLzHibQzOuMPhw6SIsrabcFeMgqSod8bJgGeIm2/CR6jLyqxYO2H+SR/hJCcqnFS38azAowgnaxcMMUQ4R5MRsFfrJb5+UvF15mb3zTjBvpsocdgJbCl7ce6etnOXeWP2uCZ+Kkdi5y7YvPUSPfdgTAtJX4oTgjEppocxKE3oEj2PzwzKjSIpoOqEQM7yiMwQv8D6THLGMmsbu0EXN7CG3aBYn8mM0s0ZI4nn0uCQrpWXVI46hufDjNQrpFd2qOCg+d5eSwqE0zJjSKPOieLrwGQqwXg9qR0KqbOCiioOx4BTxtjyhVB7sz5abC2klWaC8vHRI2sVywSrBVyzqnmKjRBQVDA/jo5VIaD2CdE0g5DGkHmF0YdXk2OaIHbenzswpQWSev9ysi+a1eWVf2Ly2HlIs8Uk1eUZ0JA6Xd7KfAhA7YdmI0WU7Uvdap+4gaV6t15mOb87bqDzMicUd7BFqDq2IHf6aqgup51KFINSretG1+qmKU7tNwjJ6F9Ntsa6k6+ButNxDJWjRSKvElSBmngsuGgy5DA+N8sWiCEskRBCIe7odNwcw9LImEFeyWlqSyagLjB2a5FeY4mUM86udAxk3WoEB7c0zg33S76VXCiujIGopFAA30oihLmS6mpmTu9sDtWUh7JCe8Ap0DeBgztTxI1RC902bs4G2MKyEZrxPe7lB7Pnjai8NBdQ/uEL6If3QoifzTOW8ef10/z21mhsBD1sWIa8Kv+5vF23BRSvnwLesW/86V/lwrN388fF/n5/7hWv3L79/GH+GLQJKHQTDj/9gcfaPkJwGNWGRzf72RIcfVqap995dUow2bGrWZVfveCvy5U+rlfbX9grPuuj0mi9YBlyHG8CASnZ4OwVzEawV64W67WmX//++rvff3z6iVyp65doFuAu6nFk2XNmVnaJcIyO/uMh+9Giri6BPzWvjNkZllQjjyEGt1stJ4S5q7nNW8fThn4in14JuVjhO8b/4L+++we//2UG1qWP6JuoItIBne/Ka+fC14TiybfQzCnhFYL6biMGTbormxe1cFCohL83O/rr6ufr5/sF+/Tvnxb3P5P7EAmfavB5wEys5bzmRAIc/GGUbCMbt+1ea2QDhqJrkGyRaBbfh3QgF3ViHxKI0MOOgDZZqJsSh6+b7mQQjGqHJ7kt7hpQvG1n8tZXi+YbAvdzgnEBJ45BnAOqYVIMmmw8wJljEDAe4PB1WWEQY2REDGI0WvY6uJ8BswAyxiCz1SXZY4KQcJPoJLZhsno0DcAgislhBjsKhOJnLfUHoT4+/6Gu0tggpAJBSE0MQlzgwsnEE2UHjOGdbCSlwIrSXTEyGOHTtspSoJEzHdOgEdAQKy0a2YUvcDQyHOFgw2xyy0wJAD7QEYAkuAJW5KkBKXJeUWRAauQaxcAjc2y47lWpgZY8Ns86iYmGL36iSHgE5Bq1XDhhDAF7MQShnHXCsUgip4WQWU2KtDgUkER0waEmDmGoWRDQ5S0eDsXvjv2N4hAPxSE+OQ45ZRNGgR/sLZLInZcreLyh9uCGhrS+zRiHHldPsQ006QxkmwkmAHcRUAxDXc4YDYjAHrFTA9E5GGgESMJruXBCA03sfTkVYxJyjMdIlcOZvRVTe4wsJ58oIKXwGEkvYAF5jNICUr8WihdACgYkEgpIZGJA4gL58HGUx0juHeC1FVN7jEiA8+EbByTXhZ0DIE3W5u7cAYmFAhKbGJAgF/ZxgAS5sCcApNPOMoruOjKasevdk7aKo94lhwNFzdFcR+SSZhQJj0LzjMjUiUbUOybFEfPZMPUcUdJplhIbh0470yg+DnnDhGAXtk7pwrZDZy44NDYOhaYakalzjar0xjFc2KJqMTGZC5uetgs7voHGNHJc2LKaeVE30IDeQNQtNB8NiOjFhR0HiGioC5tO7MJmUvkubLU32gb0fNPcd2ErjRMbaLby7QTm/kQv+WBc0kLrQ3PchETEfNwyx40qEm0cEEy9yVzZJzAgISJskVDYIlPCFtWkbW4BoQVSIwxHaLsJk603iQ1uE7jDcwU3zpCXpISAmlpGE0PYZcbLJBAW6hqn07rGmSyP1Goip20lOC6GzRhpu8vEIDaBC32MyYyJQEzAmZaJQWwyj/m3DWKh/nQ6rT+dEd0CLwLpUUCMyra7cN56l9ggNoH//YRAjNMcQGwyd/u3DWKhzng6rTO+A8RUChATdEoQYxfnfYcDzXPeC2YbcHU57xE7zJHH9W26OO/jABcLdd6zHJ33WHrZ4kc677HyMtpjAxK5AFIHICkv3dNu2nSAdMk/jwRIJBSQyMSApISf7omll5wZDkgcUT/dEysvgTQ2IJ12/nn8Cj2mbE7yHpAIkN4AcB9R0QDpkn8eCZBCnexs4vxzJhH34YMfk96gJKBzidTpDSxy++NT8jv5bQo41AyZSlWA4/Ji+Z1YgG8wHfwM9RkN8k+l9DNZUegGIzklGFHcyMFRzRaVTOOC4n2GztDxNa33wKztHrERK8AL+w0jlnlNj1g8wBF4QazjEUuHIpbOF7G4RPERS9M0iAWO/OEBDtbRESt4vm0/nuw1XEJpWbiVTVwJUtgNqGMU1wVUVRxt6CUP8A1OOM9WUcWlYJwRRDHbQkt9uK0kkhobgmrKpQ6adAuyCSGhk27j8YnEm0huNYuaOByjkTm+VDWmy9fIJ5lqyydoPtlDD4lILkpxDWtd+WYSG2pVWAu0m9QimjYCU6pfx8neIw5z9t0M0TVaD7HOiYb2wmxGVglJHT8LV0YfwEMj8Hhf+bmHKOFMOomtUgR4JEcb4TmAvwuCeIPHcxrZeZwckFA5yGuwZ8m2tjK05t7SR8kBdxc0kuUtONLwzvJ+brEr56S6X1szNOp+j1H3ey+iTPvkWTUZndgQHk8GQ6eq5yeDWrisWBo+w2VQEk9dZlSEyuBYPrlJLNy+unCcthCIdujCNa9EWl0YplSA1fvNAFI8zxykLbdcOCEgYRvhagCSq872UArc2d5bQIqnH8PbegrGeSRAEi2ARDXLDZCyGgdxvoAUOhyCTzwcwgCSa1wTRY4DJHdBCOFiA9IEIyJyjVoajGpzIHKeHUZdrLgkGBU6OIJPPDjCYJRndLEjMcrzbOD0GHXJBdtThLlThTg4YR0BYad4OHRJBEuCQ6GJYHzSRDDDpIi5TMoJOgaHiPYW1DI5Dp1OhtckEyIQCmzITnQRKyVeZJnh1TdQNCgcmxSKQjO8+KQZXkroluwrLEfJScUYt92FMDVhVqp1618wCx4igZBvx4FzkAmNh1lZ1RWeLWZZUejErO2FU2GWZm0Zo4aHx8Es3XYXwhLlpcL7fzrd/5KMBnSzhCpluKPwMN7gG5FV4eH5IlZoGaKYtAxRtmKJkq1VOcGIhVpxUfNWXS42Yp2Oh2oKyxBGLMgyjIdYWbqozg+xQl1UYlIXVbtdOBZitduFEyPWxZfVsAvd3BBi54tMhljy4slKglihniwxqSdLM9aKWHwkq7DtLpqTCRHLSt8FsbYN+1yrUCtAx0rsybL3u2BWVMyyotCJWXLSLE4i2l1ZahQ1i6h2V5aYUs2Seed7pp7S42pZ3KZLNdonQ6kLLcx3HGJd0jyTIFZomqecNM2TUo4KUcOS5iHLy4TP4xGLYtR6F8Tb7hIbsU4nIXSC0TsGsZCPWLY1YBrEuiR9JkGs0KRPOWnSJ2GiHbHoGIhVut9bEUs07qJEWsi6zKjYQxb1MuWYLWVpKFk8JWRNNqDi24Ks0IEUctKBFJvhX4fBRAg9DmTJtrtw3arKRUYsNcFAihNCLCqBXoFJEUsFOBsviHU0Ylk56EQsNekkig7EkkwlQCwh8ZSIFeDZzQSxpphOwYkE4oWAWUhRrCIcdckiTQJZJBSyyMSQpVvARBMxCmRJ2XYXjFCr+Rkbs04nj3SKEV8wZoETdaJh1iWPNAlmheaRqknzSIlAKgFmKd52l6kx63SGRk8xdIdXJl/X0B0dK8dBBeT6XjDreMwKHRGtJh0RTYRu84xrOkrE0HBz210MZrX6zAZjlvnzabVa1y8vu4X/Y7VYllf8fw==</diagram></mxfile>" > @@ -25,13 +25,13 @@ transform="rotate(-130,954.7,670.3)" pointer-events="none" /> - - - + + + - + - - - + + + @@ -50,8 +50,7 @@ - - + @@ -88,9 +87,9 @@ stroke-miterlimit="10" pointer-events="none" /> - + - + - + - + - + - + - - - + + + - + - + - + - - - - - + + + + + - + - + - - - + + + - + - + - + - - + + - + - + - + - + @@ -436,8 +435,8 @@ ego lane - - + + @@ -474,16 +473,16 @@
- attention area + attention lane
- attention area + attention lane
- - + + @@ -548,12 +547,12 @@ transform="rotate(225,2890.14,695.64)" pointer-events="none" /> - + - - + + - attention area + attention lane - attention area + attention lane - - + + - - - + + + - - + + - + @@ -753,13 +752,13 @@ transform="rotate(-130,954.7,1832.3)" pointer-events="none" /> - - - + + + - + - - - + + + @@ -779,7 +778,7 @@ - + - + - + - + - + - + - + - - - + + + - - - - - - - - + - - + + - - + + - + - + - - - + + + - + - + - + - - + + - + - + - + - + - + @@ -1150,8 +1118,8 @@ ego lane - - + + @@ -1186,16 +1154,16 @@
- attention area + attention lane
- attention area + attention lane
- - + + @@ -1224,12 +1192,12 @@ transform="rotate(225,2890.14,1857.64)" pointer-events="none" /> - + - - + + - attention area + attention lane - attention area + attention lane - - - - - + + + + + - - + + - + @@ -1376,6 +1344,494 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg index 3e9826fd84ad6..8a79347b52620 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg @@ -8,7 +8,7 @@ width="3707px" height="2193px" viewBox="-0.5 -0.5 3707 2193" - content="<mxfile host="Electron" modified="2023-06-06T08:17:01.045Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="0BpzzxhIQKLXKpqq79kr" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">7V1bc+M2sv41rtp9EAv3y+N4LsnuZnNSuWdfUrIl20o0llfWZDz76w8oCRQJQCBIASRkW8meE0sUKKK/bnQ3Gl9f4Lcfn75aTx/u/r2azZcXCMyeLvC7C4QQxAgXSP1X+eaX3ZsQCMIKsXvzdr2Y7d8+vPHD4n9zfe3+3U+L2fyxceFmtVpuFg/NN69X9/fz603jvel6vfrcvOxmtWze9WF6O7fe+OF6utTv6oco3/9lMdvc7d4XiB/e/3q+uL3T94ZM7j75ONUX75/l8W46W32uvYXfX+C369Vqs/uvj09v58tyFvXM/Pz2K/Llvz/Nfnwze/jw4e273/7z9YfJbrAPXb5SPdp6fr/pPfTl13/ck6vfyeVnfvmLnP88Qd9+mIj9s/01XX7aT9n+YTdf9ByuV5/uZ/NyFHiBLz/fLTbzHx6m1+WnnxV41Ht3m4/L/cfL6dV8eTm9/vN2+7W3q+VqvR0Gf9i+1CWPm/Xqz3ntE7B9qU9uVvebPYYw3f9du+4dl5e76xbLpX7/fnWvrr+cLhe39+rPazVFc/X+ZeCc7ef2r/l6M3+qIWk/h1/NVx/nm/UXdcn+0wkkCJOC7r63V40Jh2A/0ucDyLCe3bsawJB+c7qH9m11i4Pw1H/s5ddBllp0r7IMlyWDFJiS1LZrEEl+/H41/erqh9/+9Tv7PFv8SBjfPE6kbJdkKZNSXuvVZrpZrMr5mkhQTZY1CZWNnV7pIUCXefVMIgWcFvLwEs0ZpRxD9TGjECvjqpYWa3opIAXCGFGGMeVcUnuyCZCFoIcxAE4090K0z305uQu1yHxTKsh3q8fFXgBXq81m9VHJQF/wZo/kzcpQLbWWPJSDfXy6Ldff4mr6uLgulCSUjtxfv18u1QI53+qXeuvN/e32zqAQDHEBMScAYqn+p66Y388OnyvsYsaVPCTnjBJZKtP6Wq97oGDc0Li6JtaRRICl3HvlXClzsdiUsqVetNVR5QH5UVgJ0kSRQyuhgDZQIJepkBGglQf7Ctrta4AgRhcD5O1yQALbcmDJjGMnlyWOGHaWNUQQSp1ni/lhqdtflUw+E0M+aqmyVy8uhpQPbJdPabRK7/4wQTV5NIVneRiVfHafaONGbFnMnxabX/eDlv/929YG0v1f7572d9j+8UX/ca/m4Nf6H7VvlX8evrb96/C92YdFOVHvDuo4n1nBSZCw1VStPq2v5wG2SC0Pt3PfiOIIfBqrr40O/d56vlQ68FfzMVyQ2d/hu9VCPWCFTkJRA52YNEfYPef+S/XYxRwHNMdRjltzoN08WANtAVw99QmYDnCta5i+Xk4f1XqeGNagQAw1oI0ETwNuNch38/VCTWPpjw8EcREIcQkuRoS4Cgcb0ISiJ8alMY6pK6khjtshfv1p/VcVPA5rw0EnGz6CLR4Nf9rf1bih/eAHIW+MY7rRR+CnIDD9Urvsobzg0acuzp979Feh5uWo5XLjIbA0VGX3c6MqjghQHEewbuY+bK1wfWJox42KE7/eq9zF8HE/AdgX9zO2X6XrMRsgrmBBFtKD/NPCNppm7a4brWCB9TVGO5CNZWNYU6n6WhhAUAMuhm84rEunsRmitqWa/ax1tqZy9QgRipGSbwT4k28kByVkvH22owftmOlEdO3K3culs5fbf2LmVnYY82qtRxSgekGSSiwByc7BbGPf6KSvTdUWoDXA2IF3NAcPYMOp6Wl/DdNgDpPY3kIQvKkxuA0lkjZ2KIxkA2WSlSaWYgmAsrB2ho0QUbDa9/Xuch0OmJFCiGoQLoz1LppSQxDgkT6rLYzKcg+8hbHH9FFkYVbgw56ViSvMa5teQjlH1F6oh93hUItR2mXaJajxxQRRq5yQR/kxQoVO1gySYYcgIKSJLaYRt0Da5DcprTfHRDCBAVeWFTQDFgRpQenB8kp7BxphZcDZoDIMiD9OSbFVMkyUYtO+mloYueGvkeqNoM2S7Wex0suVm9Gatqu0qNX/2185lgPIgc86kbLGrb6M9HMO/TeBSj2aa9XAvmNA+BgtOd1Bc0bdLEwDdZIv1CEBXhQGJ6KQ9zbC9MuCsN41Ee5/VOF80qR5bAgSJQOGX5TgMAmELgpIzkMBCZZNWDYdKROVPTMRzK/m5lqTLFHhLKMN3s7pkHvokM7wFasyFVDWpqYxaxOuQuaCHJIQe8TVAxXZ+DrEjswjFix6neW3/1jNnshfdwty+dP6H3/y3/nV1xP40pIUzhS1mmCXnZxxeXV8+6iOOS+EgwuhsQmMZlEZ5KAYMjnhBkzi3ERo3d8I4pkwVHDGOMGMKX9fVBur1ckcl3wQc8gnRkDrFk/inIRbfUQW8ikTSC7DqpdNIV3i4Y5lPJ14Eqcb0lZldhNc3R3zmhLD5Rst6vGiB/Kir5vlRyW1Bo7nWbmnfcgovgMgHdF4KNQyQVBnSYeHyt6RsQ3OSOGx/4kO940VErsBmz4i7gLTU7bHQwFdD1C963wmyO8O0FDoqyG9SoUTms/pd+8uf/0NPHyznNz99P1m/fbqowwJTE9xsCTj+A0Lc7DKa6csxMGKdVCTY2TEu4xLR2UTdB0ejFTZ9BP66y3jsxW8JfRP+uvdv+nil9RSOV4TWjm5NXnJIKc3mkwAR4ZMmLT3R1V0wgrmqIjgsPApfKhYrtjD8h///PWbGVlNFu9++ec//4+/m2D0guUCCc9ALs7H6VaMa3t9zWUSd57HTJat0qBh4+Q56715NylzddY5dmak7iJ5Zq6bqZ+Oo7pjThGeGsI+Z+wQXU0dAzsMMuNXpcQO2ecRk2InIPR8GdhhEJqOlAA9XWQ1GjXdMmV3wg6u9cAORea6pk1mUux0iwJDsDObPt5VWQ57l/RD+c8ZQ4wZRzuUQVHBFO8NMns8lm5T0D3FAW7+S7EfDgOOe4uWGoeLkq499s3U2lPQAUwIDih+b8skNYxGiYcf9t9drTd3q9vV/XT5/vDu5Xx5tR1L75FalmYP0mYU9HxQybCxlxKOSiqENRoyRouHSvunYwa6/0LjSyfj2JmDSkyB4yo8lhEPcaXJTFmi4MBBVgQgKKij4oKjwvSYoiWnEidBzlNcmqkvP3HFD1Keu6NpsvcxRoxxOvgiUNqjhVn9HubVCYCQHdJnneM3/TOmK5HqqomAi88qUo5/Jb77a/rll3e3b99/++6/8OfJ5Dao9GismkBphfMSO/ZFWHkExp41ZeYKgKFE6l+BuSYPiz+DsXlmDWBfTa/FzLnCIEwInTlx65d1O3Ct+T0c2HZUXtFyplNNbwjnWlXs2DK108eHHRXzzeKpFIc51wCIqXvrAwDKgWP9v9m+ksig2gYuCKOElnQHWDnrTTsiCwgRqZEkWPqBUSFAWVnHCYJQZ7OblbHuS+LLMsBpiyPLvQNhuwVAUpcYK27fZGJkuIBIQgogJRCq6PyMxRiSMUorRlSjYh5WGyEpaFkfLKgoT8NDeB5ydLlkdHR1ZNtXDnJEDTEyWECBqkUP2iWuGYmRdMpcnIkDUjGEsEKSyokzd/+p4eIBW1CEF9Jx+pmCRNKg4xrH2fxm+mm5yUCloHHSgsqC4YNOMZSzTtGAYg59AOdmOX/aJy4uu5VM6mfnBQISA/V0lAqowtPdSLrHQCGB8gCV04C4BEzy3Rn0mU6GQGWsoPIpqFIAZVKFoN2lnEneQz1EIdGBHcrgxi25+Hvux0DSdeTUFeMBZmLoE6lDsEnbwPTlEernHXxZ+3ptr++6THA+gUpNrd1BXXLYI78nsDla5dIMhOcQX/IVz3U8+7Y16nj2XZcPnrkkhdQVyrXiCF4QToxwqAfAncNzBfwCmCU+iYHerVxiIL70PkDvRSXQB+jeKuY60r0XZgR1REwcwv5lIhyaqAbm9n5iRAdsAbwiut10O44Z+a7LCM8AFoxZtpWKguODw9y/kNI5vloaUAGSESM7gZ6ILtu1C/lMfBTfaa1Wnzs3oJdoNkDIcW/Dza3iJo7AsIa726mBYfB8hoZblya0Wm59YTaIZog3j25OGJH9DTVC5miUDHyOPiAtMlI5gtJuZM6ORP7uj2G0RDw6LZE7ZAwoVHhWtESuGj5qmzkfJ28dYH7AhqfJja42mNcZwyrxD8JG5MZJQConSWnluGKRTbEg1CqXZCxEbrEkPo59CoG1lxc5prDqOnPYZNcnfUejIDr1GNWomc+OUmpPYeaVsMGGm47Lcsraom025wn1l8yDqhD5x03sOQUUAYxCI+wnIPIiLRcAdRR0MAsLb47bgstIp3LMp+Fxj9a4BRrgeQ63ORQtieIFb/sOTl7pkY5oDN93N5SHjGolcXySjmd+DoVTc2eZ67rBPqlgczSuYDAsAuJTbTxvBHCMLcod8+xQl0oFbo2GB0bASz+JZLGNQTt+ggg46JMinURyiyXxAdzsxWLaWUqdYkl3QMy9OZzed3tumwxeeLeyUOoLs1kAXJsM0DhNd9ImA2HGaKnrHXLeZJBlu0YBuPq3ojk7OEuc1D5F9mFI9W7BRHUBJzYujEuYscETjz1yBEKF8E5utmj9UAnvNyBJwdhheo2aNUhBwXn1scPEYyoL7kgs81SJ5RALP96+EBdYUM4IJQhgSKx9IcRR2R+PY4kpl9TcF1LOThhylMEcGzoQ0IIAArAEmApoUkNBQAoKpP4YCvv8OFUjCIeDQAGv6DDj4yfAnEZX9F0D7FHFJZiSVqXJgjYVnRKopHWwA8gSlnOLIoaWu+uzT818nHH/q2Dht9f4Obw474WZeHGUsrrjIJoxOISyEOiwKPUs06ZN78S4CWl8SKVhjlIfTwhI+4yxP6J1oUCANvQBCunXCPWH2Vm0r5b02qUJ1hntX7TqDMkr9UWF9MAZcxxFZ7DvJgR5bxJpS4gS728Qrt9w7HkI9Y1FnZOWdO8JdWOeynPvqV+xsFZqmEKpQ7e5MlNqjHz4ZDSKUnO/DrAeOh0t94GSq8Nzq4H3biK0p/NyqxnmWIv8sAMjwOFwXR92OYu82jliPGi//fT+p4fP7yd39O0fv3/39MP7X/5zOXGlMVhFhdCAOPvvp5X+YPK4PWb/Rl2A6cPTFir6c/Vft/v/vx3oSr/x0/pqel8m+Narx8f1ajp73EpQCVBBYj29uVE6g8ByK779d9UzXVnjrQPe0W/87Zv5zWZyN72fHW7y9+PfC7yfc16uptd/3m7VfHK9U+xyehb3i81iy7Z7fIZOmGpwXdmQw5uYXYv51Y19w/ntqpzhqXLNDw+8u3v1i6Yfy8zC/dXjNsEwLWX0sF6s1qUJQmClQv1yJu/m5qUdJzX3KdzvZh1HdfWYXxbz5Ww/rY/H5zWaUjVm/VZZtXstkGNa5NOYnWlc3Zdy3mvJp/X9ZLZYz6+3eaOD+IuWh3PJ+ciljw9bS9A+DyDUuHSDn3pv9xP028Zqvpk/bZrr93Sfo10qe3Jhp24/LmazLc32eq5+/X7volxC93GEGpVeXtB35UifNqvdEzpqH/Zhs4Oyptta3GkblcJmGfeEE7ofp7bAVpTXjYMYMkLuzbkyJe4f60yQdtzZPiiJuuH8cZNUSpTYRMWObDasOn0n2Ox2Cip+O4xuk5iNk+iSkDnr4Q4ikdIYjUOTgCsa6bx9M/XT4xa5OrHTrQ3C88aOGWAQvf3RCzvmaDCwYKwXdqyfHjlJ5cROxwLpZwweAoVZHnKK4aHSKqFIZ3ioBZ5BDE8QQ/JrRWtNUAIZTiKDBPdv4uQYj2mq44FyH0HMyi/EgFjLP+mbx93qtDkaNJnkYxoQ+6eL2E2c3PiJwGr12sSpEyqF7F1DiSW1RhPJUGn/dLYvIe/0C40vJcJxAJdVlN7I/rPr9V7J4wba1PSmmHBUlQMgU3YEcosqcVbk3ESFdbFuhqJ6PTPV0dxzZJu/3kxTpCKaqI02sH95Bmemhk5hmlxiFA98jMopqQHqXbqzOea9we/1JOob/N4L8zE+kprb8fCECEgCczQEktWsuCHdLS3/CukWj6sd0jQ3SAtGCylNHula+oZEoZluuQ+HlKbkm3YKA3dL770yq/s3YVvBnxv2lVth7WeZHZs79H+2onkORbJSfDegu+UqX08Ut/jk7eY8txJEgokZ6xJ92K1PeCTN0Sg2RksM6ZB2Qa8BciNApqbMuLmr2wEB1mhqpU5GLORGwGuKpHOVgMlDwlD/LThJ7NEGRsBriqQ1RcJd7LYIOPrzpUyR0IB48qVLikFHp+3Bk1k6bfHqKp4Y++wR3x78iMyWCZer2L8VicNVJHTYcJ6lz88+twNY3uW2HdK5RT8Um0VpjDF+ygEsAqXl/bhGTAxtEWCtd7xK9qbsiYtbD6olwgGtNWfg5gxSRgoS3tyB68lO3dvBOfUhHCzPvrdDyTUbxgkT5F35MR7sXpFmvg0P2d/BjZWA/NtYjQSGFAzErZJJ1uHBLZgROjyEM6Yd6fEwpMQmBiEeQvaOe7LGD85n4BHqJpsiLU8N6sbf9oYktoRVl2sstokGc8SBooYD0fATS43pSlHTERutbqCLh8Jr9TJxA5ERcUOTDym4DYXB256OV8mtAAEFl6l5lbBDbY6qQsEhaqpDuUK3KYT6yyJbOlA34SZ1E2Ld9aKNgmkoLckrTcya2OY9dQRCQ9nMRHOkYmmzhQI3NC5BwTMfh9YvROVq+sEM/UA99CNWIm0oTcqrvYehSSr6jaRKA683MsDhyifHQBG3mntvSRIj9IxEsBrENGfR3FscsLo/+7TCZIC0QgXrDm0kDWJp/fd4iYWQ5jqx41fXttr4wmluMiBpi2bYzEJI05vRWnpGTyz0UCajKA7q6Gy0xIIuh8rXrxtnz8gr8FbvTetBq/emL8zEe0PAMPYmmXtwz0GDpRzBYd030S1ciVjMnAzZjVxZLjgPLXbGeVU7mzjHoCfOmTHOwFGKCNjkzyErdkpFS5lJo02YI4JagO7OpPXJfSWw+Xkd5ELEMNV9M8TIaEGDzdg/VmdZaNwHDZD/kgERapo9s1K3ahfuXl79HLXEr1rpDyUiwlHiN8bxchnBKeizdo+wtdZNwK22TaO/1bbJvGyb84S8wlg/A6dGY9YZqYrleqjE5Agh9lkaIkhMUTHhSF2NYohG6xXRaQuzm8npYxljm6lQF0zmFXaXhsWk3uCAnGCmoDWaTGam3O1QAvylkXpfKn8EFuDQ/86wEkKKQsqq/R2ybQYntP596LIeBBZCEHOQUyzJ5dd/3JOr38nlZ375i5z/PEHfHqal+yz7pXbyNMMCYjXRAnO1ADPIAJ5PHJtQ5lSiQabS2UAmhBv1lIWVvRXvtwfpWnmiqitbOwx6MRG+WFIlLUYlA7LsuMuN+EqtpAWnPoXAghTIUZacrJVoCBXpiK1E6YW5RYiCGoa6IDIhdr/QETBi9AxFtNlF3OgZivT5nrF7hobwlcZW6mNH8IYWmRJEw7aaW0+tEsPCcQwvXePQAJ2OlsusZNGhcyKURudEOVx5UVvq0oeY1h5rGhmtPda0NmXiNis9awBck7/rROa2RaC1bnVOa2L/XUDzLomSnmU/b8+vgNL5K9J2PAywrSdGsd3VdIjd4raOh6cpIzpPZVTIawK0iU/m15JQZSTEexfYSxdjKYRuCZSqlmIobdAr3UEjyrqVHhtusVUjtMGvXtAyUQ2IZAO0vHm6iCMQY52ChmoYd8H+1TCeajhFHJDw1NW0jizx+AW2jBLzLDUXdu2Wuq6gjkAYAlQArBxG9a/A3GT2j5YO6kQ4AjtHO1fTazFzpvwRJoTOgkTlxUdwcIOalh85thi3sgD6pW1CQ79hEeOktPOJQtaCKoPQIobp44NCq/rjZvFUis7V684SCQCUA8e+zc32NaCozG41epmsR5qoEED584wTtYgL4CpFd18SP6Ma0iIpqeAugaQuwe1wPJ7g9DHmTOUWQl8aRW5KFB8+HN37RHshZaZ1wnEAJCPhhYSSSZWObV8ZyI2Ac5JbJyaBs3Y4dNWedtqJJRfCC+lgmDP7wMWb/IAt1oRKM5vfTD9VHZpHVZlmZjtzlQkoQtMbTzfL+dM+W3DZLZOmn50XCEgM1NNRFfRhyXYj6fKPQgLCaJlN5BIwyfnuY51ZgLCAkEBIVcSiTKQQtLMUMwnBaZN1SRiVPaExtjEMhMY4iaNoZ38cX3P41ubvzj7u5UspsPXd+e3qYtezvVNX81PWg2W5eXtZtbhvuGDly7U0lK/tJ/VCJ2rbqaoXw6Cdwxmw2pxhncyvnwLDjjRCjFNgbmClL0gLlUp1XZ9DA83EqNtahVaYeTUwE7Omfg8UzIBTtR52Lxxj3GqpjKkxWmob58phxbdx/AYAl437spgvZ+dg5fgHAM7Kyklq50sHtnLpWX4rqdiWqEVO1Tf72L3YVi43dl4G7dYL3PDQO1g54uijnKzVlHOGkSvL2M3KTTcbJe0yvFK/ej2f5mGWDuYmS7MEgdnAAWCHWUpFmuDGQkjmMknbsQCzVH0zA7OklSYfs4Ss3hKyL3dYuccoLBKfdP1l3DPsyue1O1P7nYmjjlhlj65X9zfLxfVmcX+797Ee3WbriONlaIXS+01TD5w8IA4TM93X/F4rZJblClYx8MfFbLY8ljdratsRM6lvHqhfKY0eAiaupGsvx6EqOJnRC9iqzroigDCrXyV1zOrYFQEowOfNM0NfIeT51ATg0feWUxUFdBfWeVUFBDXHPMuqgJMll3dZQFATyPMtCzhZenlvluGA/eXzrAvoLrizKgwIIfR8Lm5HfpUBIQSZ51gZ0ENpzqk0IIQ98zmUBqC80svPozYARyuxn4wUUXPALOoocCyGs9EwVESNsyqyPyYsP0bCs0dmTO1g0Bk5pj6rQvvE4jKXO8eZ7nyWOzJ6NqRLTD2s5HDekju/WvthxVfV5mYqv8GSIjHC6sSiM5ukZi66rCruE4tGGJv1+llHDK1JQGIjl9A6teI0M4m5K84LqbvHeRXeQ6NCAhphWfDpdrPSQh8ZGyi8JgG5GUc/qD0XlC275AfWmTBLUwizs1/Hg2k4SDBNArIWAy5nx6Tlh0S7xfzS1Kl8omcSkMyI5skDIKa1KrS+IXQqIVVsHc2NFpr1xjQZPf3RKYhOLDt+TqKj4+c/ugTQqdVOnJPoRi8H6RRADys6u1d6TpILSH08A4dDf2rX5gwdMNNxSzi6BczDKkreJi4g0fEc4mWS14lO2vRgepOW+odJHCzT4L3oweNiIpUCESAAV/8qPJknLiBlBeBVQGbbT/WlQiGs+r7DlpaEfogSuX+JCCrq7GLBAryQNK1govXB9cMnfJsay2Kbq9ilK5ho5vQhIYU4CERSu6qgpEfkjuA7Bt21W3gBjkheFPYccUwExxJTLoP47F0ActDZj48fg90eGws1BKI0CrpBAiW2i5ua3d6NoU6bQZEMAGY5WgCFybpZ12kRHU0qAwD4wQDYu+vOrsvJlJ+HZG3GadV5YvcnZTsAuWjS5MuLrjT5HWHS2hhKG9vWxlB6Sc3EG4TKs22g2qjvIXVfBfQ9EQ8Z9OgO9t8kdYfbgCRZDh1u+/Z1qKkNa6gN6qw0vXpEJFAhnJcKUR+4CTXQ3U+DMPHdhJoqFKRBnTtE9PgNSVvmipAk6Xn1YO+5NvbpFxGumPg8FRNLH14ZjKKYxK8UrI9iRsuSBB+BHz5LwplRFcekI5cM1fzVwmqpU/++SgIeoZTACW8ncZhzOk+KTI4dQQqfZXMChym/cM/Z+OwAQaLwC7w9SByl4ML5o53ET+aiGLHg4k3PgotBxFJVXBSEUUIpJwwzZhw5kQWEqGZkctk1cYt39I3h1nKMISXLcAGRhBRASqAyduKMJRuQrx25WmNQnVX+GVXTDgUVSoGR0V3yvEQ7/mH1BA7JcaUs1LKnXQuIQdPTo253bZgKArd4cj/NPqTwIC6oOKgdM1o1y4JhVHk3Dl7pnNTuhRx3p3kddyekkPxgmI1GzpwWElfeMdA1Kt2b0Rk3wV3ukjrwDoh6cqrlV+uoyX5LkH3YZqxo3DnHLCDOCaQj6FSUVcn23OJz9yx2qvAYyjPpLZwKFB3YK5vrW3YHKELKODKN5wcUI9SJprOo7g4pq8gviB9QnOyspDnuid2egfuQysnPSZoBweAZrYhH3RWPKR2/pp8FRG65ReSDiuiM6vxZQK32s4jC91LIJAo3T5n27vrecmAgcSjNOoTSebLOUWgUBSiNcNSHj806xwPi6Ux5X1hnA5o/6xwffZ8vGetcd3GdFescHyxgH5x17mTJ5c06xwcLy8dhnTtZfJkzMPHRA/FkrHPdRXderHN8/Kh7ONFkyDrHcw+4B1QcdFaK80Kia5ZZdP1MWOe4q6a50Y/P7hRafjB53Ir8jboA04enC1+X5Krr3k/rq2nZTPR6vXp8XK+ms8etvJS4ENispzc3CoQILLfC8jTtu1oHvKPf+Nv35XCTu+n97HCXvx//YuANnRNzVbXom+y7GJbzs7hfbBbTpXeKTphrd8NEdi3mV47u0/Pb1UVb7+npx9Ke3189bs36tBTSw3qxWpeHWxBYKUtazuTd3Ly046TmPoWScTxlHlhXj1lv6f14fF6jaVVj1m+VEbvXAjmmRj6V2VnC1X0p572WfFrfTw7JtIP4i04Ny72XPj5sTUH7PIBQ69INfuq93U8I7vypO3ou5zflJ0f7ea7n6tfv04Pl2rk/VqdGpZcX9F050qfNaveEnVqK2itlrAaelEqzgSeh9i4QczbwlMl8Ulfqt1sL65DesuXrpqepzKAfdvnafpJlP2wCdf1KlfzGOs1SJ0fAjsx3sn7YznOjr02Iz7sJMYEGd8GEA2EH1sM2IdY/ILEJO+aq1B2TrI1Y+QBvWAccjW3EJBrdiB3vpB4Krelmo+Zq5+KpaZvmgYWDjPPEgjBdJQAdWHBRfaXDQkji+zQihFA3o7quIh65COc/aJIsuLNDPkHWqQy8LmUmWaStaTEIAhkmPSs1ylP1khmjETPzmDihJELOUp0GxWqxsOESajL6gDMyFLVrkA8UkclVyQTrmdZUo1FmuGOMmY0vU0MxZE/jNChWgDpvKObF26LAg6EJHql3qHpAUdiRgZmvjwfFj9+vpl9d/fDbv35nn2eLHwnjm8dJ8Fkltz9yrOosFAO+1A82N4qZALyQUmquSgdDLSEFZhWZJXG4OgaJLUlFUBnSneIUgkr2Vry//HBhN5SORk/pxUt4oQaFSiTmaXjNQcZxwdFBoI6oGNACOk7zJeOnDGlNkRc5bRAfrQsuE4ijMtLGAQzEuAC1A7SGFYCAFBQcIKOX7rEJaUP6YsTW9301fy4CrCRE6xIC0g5CsRhUpdMHoZV0mu4WsQWRE/ueT96t5Hsa8K3ke/rCTJw4QQ2DwoQTrl3dOWmwiSjT5B03MXtsUN3UCYSxRxDfiWe5UD5YE9FQtkJa/WXRv0aJVE7SBpJX/oaB5slGRlkTjP0wroYtAAGQA6aCZqANq66hpmrd5Uq/oCRc/d9h8R7AgRiNLfkE8NdYj0UDrlB0Jwvvzb3cwpfsU4Vzs/clZjllggoVHQrOhAOzHDFWUrZJxHumOLFROgsJ6GP9uzIfU4MeRUW0rtvGIjt24gKduNDYOuTET/+UwlDJIY6xsQNDOTUyi+HJIYbM/Rx7tEgoUj8dmD1z1c0GwE7IuZaXih0qjXE6YEciczQrvIqGHcfNdNVWUux0i+qeMXYcloKatW8dsMPNmgKKzN2WeNixb0aFiptIevh02w4Mgc9s+nhXuZf24bkP5T9njDJBbJvS30LZo1mYTbz1AQMQMNLeB5OEFlIyCnFpXo1NIsq5KPdBOJMUHBjy6kCAsMC0+jpyJEMJggVC1Rg4RmLUPc0BiYjxEuoMcQExVzGtcpkhtrLrEKiZoYBLzhkl0ky1M25nap2tw0hoovYo2Frjsx2ej6IKswYkOG/uqWNeIIwRZRhTLgB2kCzq6tQGCQSXqXATcH4sdoe30YUEkSklS0g1nXW0mxaJKv3cDxOQcxmvC6cyBLPF/FDb0KjASyC7iVD2gmAimMCAC46a+WBEtnudHuEhOajwAjaoE3QUi74lolZCI4lcNqnskv9y5pQDvDSvV1FPk3mUZ7SsmKz7F1r0elu+xTcIThf7bgKxcBmzgZy/kGYkqZvruVTh5J2+GNit73Z4DX87yHm2IIdl4+SaEw177vtB6LuLYN6bRAqkvQ/Knc+ZNiU8Wv87z/LSZXew78ZKes3jZ6F5RCmXCqeIoGXDjXJDsOkLAeXlIkowF5JLKkXPal7axL1BtQyFusthgRHpmty5lSCYIHDw/ALHqBlYTMoGVJZDCgFxEIiUxsYDiJOcUhywLEePKHZVVI7jIkdYsPQY0YLCHVK8uuoRxaGZhCaEiS+WRPa8brWD57mvj9TXNms9bjW5uL2rQkpnpyCESFBuAXMoBDHSO7QA9VdPj77MSyKKMORQCs5Il3skNrcY5WtuqzLzg7kVUE0WBohhLAiybS8FspaQ41JTyDVpPoFjkPjaH7BL++wzuDR9bnCH4KM4QhIWtbJoSZr5Jczd+d3xMrg6hzzkYh6cHUwnJgp8YkKilNNBZ6Gt+li4lvpUeUDcieAwqss1jpzq+lLJgVaL2XiCSH8qcKic7DCOmV7xW4NmHJqTxUcy/AO1hRdIBc1MKvdNxWdQNn2GMpilouxsiJFa8kyrHVyo2BiUFZgddIDJYQ8f4oAtvmNJ2IxzRucLfzIq/GkzZIGs6d2afAGhiCfAGBf6x42UkyXGws+dd01bXRmwPzu8ShUcNbQKYeLXK0fhe3qdwWOqAsEGZGUkVTCyAv4AMrX1zzc/ykRzR6UxaSp4B8hff0VU8F4PxhxhFxaysf0ZoXuKu0o26/PMz6j8Ch9J4rrLr/RRd3f1FXG1fRk2eCcBKd/zK79qEZJZftVdSmjQkJGg4YU0YgFWi/QmDBesVoBlHGlRLliz4MRu+YJ0Nfow0jv19MtZRvtxSlW089DqyGk71hr8kFHr6wkgLo9Bx/7QMDz93D9MfTfB5k2S9dNzz396loY+wUppEhrRiuDDRSvBIB9151ES36Jp46ofeBn3Ls1+dzo1dgNy6GNUE/bKYo1gnsdCrgKTD1QM+S1ihzpYz11Kp9OnIJHyURD0edZjjyS8g3FzsBOmRzhnJ+3J0oCdGN3a1VFI1PShDSbG2iczdsUo6xDepKwHM+hZKWM51IORRBlMb+FRJbGRC492MBzNNgJsHD7qav3090ghKbH43IZamrv26ghtd/PjZJf0QuCPT/e6H81n9RvL5hw9ut387Zv5zdF2UBc+4vMMO8KYLDhHTdrppovq+LwyXRI5TsQyh6ZAkiq0d7IBvnaISdYhJgWyGKLSQBaRjoxfquYKbmAFZPzOmVC/Jy1CQKRBx+ZPwAZd2oRiXdTZhz+Bm2aPpGMxd0/oa5+PUcySmbdTvrpOcjYOEyfq8+HGQvrkXahUzs0sjVpoUK5y0Az9KDJg0sEsmUU8Cpxo2FwcjU/scxIGxhMtJUDUS5Fthrfeyw/BtNvQ0RijKGTMf+cBCqvoqeS6LwZjJ5DYETWab+h0jHZtdx6E3o4GFMe+DIy1GZsTyO6Uzwy8GEvGfNd258Fo8LplWF958IiELWbpBIvnH3pohjxnn6osc6ffl1e+Jk8791hi2Au4DDKpEAQUIo7WooqbGUK29RxUzIMYJwjYJWZku5+pPsTKkT2cuGmUBhNZCFqNwc1t52hzqyX5omuDBzjYu8fwUSSVW6gA6MJFs5FI82Av1p+OVxrMAjTyDM/1tkkJq0gH1Ng2UENKStdLMVlKW0/JoSFrg3Upa44F3PGpGY/JrqFDPuFg17KWTjjZlf72O+mYG/midhZaq321drTmZ3cXjhVuMNpYGFDTQePAuTJ0LgsmwrP8tNwkcQiiT+XnVlk5Lk+jhnkgekP0YdSoGhPWH4HBMJc+LwuiXjjvfCoYdH/SpPkf1m27JONj90NRNYYrX/BiNO7RE+aDZMnkGEP7CPMtMmzURUY59e1KMFqOAVHvfheX3YjEHNVKVMUuosZJlIpGkL+0fIOrae8g+YYj54EqJrFm7JpdhoEnzjCc1Dw9oVx02ajOKRhcYWMzVPHEKYUTe1wnEExdQQ48ScRO6w4siG7pg2E6WoMCcc3k0v+s5PDunKPFr3f1anXn+Kgpg0FYxNQ62XBKYNMtoU22moFPEvMhcwY99KRPcDPZEvU0VYIg0ZpucCTXYuUggvUmNAwaWW9S0Y/Rpqo0XS/aT1XOkIyMn1qXGV0Rz4ftIoWyjZtzSERwRqFP2SChfZj/opVa5Ztl4NiqAt9XMlRR4YWdWCD1k9kQOzzgkghNeBI70TxiFOARv6YWLk6OlGhLBCushoV5ZRZQgG94hpmFNrHIpnarIKFNLsMSmaHEJOQusYxWrHBMWME6U1GXDSObUw87vGDHjYb6bdoutfptaFSOZmLwhxu0Zf13h3hzXIOpbOgNIdTt7MVg+bWuXGR9sR+RwyxcA3CoBoxK0o8MpMo4CoBNxRoX/wGHQs4mgzaCHR/NPGvuMB3wYlgwfIAR69s0gjfzu012bIzDiMO7J62MpwHOpzm6puDm10W3b8OQR06aMVNhoUMNX1lkzopFhuTIIgNhooaOz59GZq+UY1n47WnYiDwyZHweGagJH1+JZAa2TNjK+Y5OJANh+tKGZ8oks9ejMS2T7hN8OLHcn0qGcGqOxmSsQgL153pVWpDD5WVC/9+r2by84v8B</diagram></mxfile>" + content="<mxfile host="Electron" modified="2023-10-03T02:31:58.208Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="OqfTL5XvOGIvoGzJGnrd" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > @@ -23,7 +23,7 @@ pointer-events="none" /> - + - + - - + + - + - + - - - + + + @@ -139,7 +139,7 @@ - + @@ -176,9 +176,9 @@ stroke-miterlimit="10" pointer-events="none" /> - + - + - + - + - + - + - - - + + + - + - + - + - - + + - - + + - + - + - - - + + + - + - + - + + + + + + + @@ -663,12 +687,12 @@ transform="rotate(225,2986.14,656.64)" pointer-events="none" /> - + - - + + - - + + - - + + - + + + + + + + + + + diff --git a/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg b/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg index 8802dc786b617..c29cb7ade21cd 100644 --- a/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/stuck-vehicle.drawio.svg @@ -8,7 +8,7 @@ width="2842px" height="1201px" viewBox="-0.5 -0.5 2842 1201" - content="<mxfile host="Electron" modified="2023-08-28T08:00:31.600Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="CbgId97oWJwBUVWni98L" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + content="<mxfile host="Electron" modified="2023-10-03T03:33:38.127Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="TqIhwSEqRvc68Imy-9XT" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > @@ -18,7 +18,7 @@ - + @@ -57,9 +57,9 @@ stroke-miterlimit="10" pointer-events="all" /> - + - + - - - - + + + + - - - + + + - + - +
- +
Date: Tue, 3 Oct 2023 13:29:06 +0900 Subject: [PATCH 6/8] fix spell Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index 0f47fecc69453..cbccff29bc562 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -831,7 +831,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( "Path has no interval on intersection lane " + std::to_string(lane_id_)}; } - // cache intesersection lane information because it is invariant + // cache intersection lane information because it is invariant const auto & current_pose = planner_data_->current_odometry->pose; const auto lanelets_on_path = planning_utils::getLaneletsOnPath(*path, lanelet_map_ptr, current_pose); @@ -975,7 +975,7 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( } // occlusion stop line is generated from the intersection of ego footprint along the path with the - // attention area, so if this is null, eog has already passed the interection + // attention area, so if this is null, eog has already passed the intersection if (!first_attention_stop_line_idx_opt || !occlusion_peeking_stop_line_idx_opt) { return IntersectionModule::Indecisive{"occlusion stop line is null"}; } From e59f18b953385242ce549ebce07fb3c1fdc9bd2d Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 3 Oct 2023 16:15:04 +0900 Subject: [PATCH 7/8] add data structure figure Signed-off-by: Mamoru Sobue --- .../README.md | 26 +- .../docs/data-structure.drawio.svg | 771 ++++++++++++++++++ ...intersection-attention-straight.drawio.svg | 152 +++- .../docs/intersection-attention.drawio.svg | 190 ++++- .../docs/occlusion-without-tl.drawio.svg | 295 +++---- 5 files changed, 1177 insertions(+), 257 deletions(-) create mode 100644 planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg diff --git a/planning/behavior_velocity_intersection_module/README.md b/planning/behavior_velocity_intersection_module/README.md index 1dc358ab900b0..16459bb64074b 100644 --- a/planning/behavior_velocity_intersection_module/README.md +++ b/planning/behavior_velocity_intersection_module/README.md @@ -24,7 +24,7 @@ This module is activated when the path contains the lanes with `turn_direction` ### Attention area -The `Attention Area` in the intersection are defined as the set of lanes that are conflicting with ego vehicle's path and their preceding lanes up to `attention_area_length` meters. `RightOfWay` tag is used to rule out the lanes that each lane has priority given the traffic light relation and `turn_direction` priority. +The `attention area` in the intersection are defined as the set of lanes that are conflicting with ego vehicle's path and their preceding lanes up to `common.attention_area_length` meters. `RightOfWay` tag is used to rule out the lanes that each lane has priority given the traffic light relation and `turn_direction` priority(`yield lane`). `Intersection Area`, which is supposed to be defined on the HDMap, is an area converting the entire intersection. @@ -54,10 +54,10 @@ For [stuck vehicle detection](#stuck-vehicle-detection) and [collision detection Objects that satisfy all of the following conditions are considered as target objects (possible collision objects): -- The center of mass of the object is **within a certain distance** from the attention lane (threshold = `attention_area_margin`) . +- The center of mass of the object is **within a certain distance** from the attention lane (threshold = `common.attention_area_margin`) . - (Optional condition) The center of gravity is in the **intersection area**. - To deal with objects that is in the area not covered by the lanelets in the intersection. -- The posture of object is **the same direction as the attention lane** (threshold = `attention_area_angle_threshold`). +- The posture of object is **the same direction as the attention lane** (threshold = `common.attention_area_angle_threshold`). - Not being **in the adjacent lanes of the ego vehicle**. #### Stuck Vehicle Detection @@ -68,31 +68,31 @@ If there is any object on the path in inside the intersection and at the exit of #### Collision detection -The following process is performed for the targets objects to determine whether the ego vehicle can pass the intersection safely. If it is judged that the ego vehicle cannot pass through the intersection with enough _margin_, it will insert a stopline on the _path_. +The following process is performed for the targets objects to determine whether the ego vehicle can pass the intersection safely. If it is judged that the ego vehicle cannot pass through the intersection with enough margin, this module inserts a stopline on the path. 1. calculate the time interval that the ego vehicle is in the intersection. This time is set as $t_s$ ~ $t_e$ -2. extract the predicted path of the target object whose confidence is greater than `min_predicted_path_confidence`. +2. extract the predicted path of the target object whose confidence is greater than `collision_detection.min_predicted_path_confidence`. 3. detect collision between the extracted predicted path and ego's predicted path in the following process. 1. obtain the passing area of the ego vehicle $A_{ego}$ in $t_s$ ~ $t_e$. - 2. calculate the passing area of the target object $A_{target}$ at $t_s$ - `collision_start_margin_time` ~ $t_e$ + `collision_end_margin_time` for each predicted path (\*1). + 2. calculate the passing area of the target object $A_{target}$ at $t_s$ - `collision_detection.collision_start_margin_time` ~ $t_e$ + `collision_detection.collision_end_margin_time` for each predicted path (\*1). 3. check if $A_{ego}$ and $A_{target}$ polygons are overlapped (has collision). 4. when a collision is detected, the module inserts a stopline. 5. If ego is over the `pass_judge_line`, collision checking is not processed to avoid sudden braking and/or unnecessary stop in the middle of the intersection. -The parameters `collision_start_margin_time` and `collision_end_margin_time` can be interpreted as follows: +The parameters `collision_detection.collision_start_margin_time` and `collision_detection.collision_end_margin_time` can be interpreted as follows: -- If the ego vehicle was to pass through the intersection earlier than the target object, collision would be detected if the time difference between the two was less than `collision_start_margin_time`. -- If the ego vehicle was to pass through the intersection later than the target object, collision would be detected if the time difference between the two was less than `collision_end_margin_time`. +- If the ego vehicle was to pass through the intersection earlier than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_start_margin_time`. +- If the ego vehicle was to pass through the intersection later than the target object, collision would be detected if the time difference between the two was less than `collision_detection.collision_end_margin_time`. -If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless _safe_ judgement continues for a certain period to prevent the chattering of decisions. +If collision is detected, the state transits to "STOP" immediately. On the other hand, the state does not transit to "GO" unless safe judgement continues for a certain period `collision_detection.state_transit_margin` to prevent the chattering of decisions. #### Stop Line Automatic Generation -If a stopline is associated with the intersection lane, that line is used as the stopline for collision detection. Otherwise the path is interpolated at a certain intervals (=`path_interpolation_ds`), and the point which is `stop_line_margin` meters behind the attention lane is defined as the position of the stop line for the vehicle front. +If a stopline is associated with the intersection lane on the map, that line is used as the stopline for collision detection. Otherwise the path is interpolated at a certain intervals (=`common.path_interpolation_ds`), and the point which is `stop_line_margin` meters behind the attention area is defined as the position of the stop line for the vehicle front. #### Pass Judge Line -To avoid a rapid braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) are needed to stop just in front of the attention area, this module does not insert stopline after passing the default stopline position. +To avoid sudden braking, if deceleration and jerk more than a threshold (`behavior_velocity_planner.max_accel` and `behavior_velocity_planner.max_jerk`) is required to stop just in front of the attention area, this module does not insert stopline after passing the default stopline position. ### Occlusion detection @@ -162,6 +162,8 @@ entity IntersectionStopLines { @enduml ``` +![data structure](./docs/data-structure.drawio.svg) + ### Module Parameters | Parameter | Type | Description | diff --git a/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg new file mode 100644 index 0000000000000..fb512902ef856 --- /dev/null +++ b/planning/behavior_velocity_intersection_module/docs/data-structure.drawio.svg @@ -0,0 +1,771 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + closest_idx + +
+
+
+
+ closest_idx +
+
+ + + + + + +
+
+
+ + stuck_stop_line + +
+
+
+
+ stuck_stop_line +
+
+ + + + + + + + + +
+
+
+ + default_stop_line + +
+
+
+
+ default_stop_line +
+
+ + + + + + +
+
+
+ + first_attention_stop_line + +
+
+
+
+ first_attention_stop_line +
+
+ + + + + + +
+
+
+ + + occlusion_peeking +
+ _stop_line +
+
+
+
+
+
+ occlusion_peeking... +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ + + next + + +
+
+
+
+ next +
+
+ + + + + + +
+
+
+ + + prev + + +
+
+
+
+ prev +
+
+ + + + + + +
+
+
+ + + ego_or_entry2exit + + +
+
+
+
+ ego_or_entry2exit +
+
+ + + + + + +
+
+
+ + + entry2ego + + +
+
+
+
+ entry2ego +
+
+ + + + + +
+
+
+ + IntersectionStopLines + +
+
+
+
+ IntersectionStopLines +
+
+ + + +
+
+
+ + PathLanelets + +
+
+
+
+ PathLanelets +
+
+
+ + + + Text is not SVG - cannot display + + +
diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg index d33674a257d9b..640eba618fa49 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention-straight.drawio.svg @@ -5,41 +5,42 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="3389px" - height="1411px" - viewBox="-0.5 -0.5 3389 1411" - content="<mxfile host="Electron" modified="2023-06-06T10:31:30.247Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="U1JUqxOsfTr30viw8iHe" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="3390px" + height="1412px" + viewBox="-0.5 -0.5 3390 1412" + content="<mxfile host="Electron" modified="2023-10-03T04:48:10.725Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="02kGXKyoYgRU_RdR3ghD" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > + - + + - - + - + - + @@ -390,7 +391,7 @@ - + - + - + - + - + - + - - - + + + - + attention area - - - - + + + + + + + + + + + + + + + + + + + + + diff --git a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg index 8a79347b52620..57552f586e63b 100644 --- a/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/intersection-attention.drawio.svg @@ -6,9 +6,9 @@ xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" width="3707px" - height="2193px" - viewBox="-0.5 -0.5 3707 2193" - content="<mxfile host="Electron" modified="2023-10-03T02:31:58.208Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="OqfTL5XvOGIvoGzJGnrd" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + height="2195px" + viewBox="-0.5 -0.5 3707 2195" + content="<mxfile host="Electron" modified="2023-10-03T05:15:42.124Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="WBrLRHcQvF5FOJ4jcZAE" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" > @@ -128,7 +128,7 @@ stroke-miterlimit="10" pointer-events="none" /> - + @@ -139,7 +139,7 @@ - + @@ -176,7 +176,7 @@ stroke-miterlimit="10" pointer-events="none" /> - + - + - + - - - + + + - + - + - + - - - + + + - + - attention area + attention lane
- attention area + attention lane
- - + + @@ -678,7 +678,7 @@ stroke-miterlimit="10" pointer-events="none" /> - + - attention area + attention lane - attention area + attention lane - - + + @@ -899,7 +899,7 @@ stroke-miterlimit="10" pointer-events="none" /> - + @@ -1279,6 +1279,134 @@ stroke-miterlimit="10" pointer-events="none" /> + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ + + + + + +
+
+
+ attention area +
+
+
+
+ attention area +
+
+ +
diff --git a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg index 086557f1a5bf4..2fc22c8a4a401 100644 --- a/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg +++ b/planning/behavior_velocity_intersection_module/docs/occlusion-without-tl.drawio.svg @@ -5,32 +5,32 @@ xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" version="1.1" - width="1882px" - height="665px" - viewBox="-0.5 -0.5 1882 665" - content="<mxfile host="Electron" modified="2023-10-02T06:44:01.727Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="EbltkDSNts3KofHAusIm" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">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</diagram></mxfile>" + width="1653px" + height="522px" + viewBox="-0.5 -0.5 1653 522" + content="<mxfile host="Electron" modified="2023-10-03T05:36:02.775Z" agent="5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/20.3.0 Chrome/104.0.5112.114 Electron/20.1.3 Safari/537.36" etag="BwI40dFIjy7ASgJYnXFl" version="20.3.0" type="device"><diagram name="intersection" id="0L5whF3ImEvTl2DSWTjR">7V1Zl5tGFv41/ShO7ctjr845k8x4xplMnBcfWqLVJLRQEO3uzq+fArEVVUKFGpAcSz62RQGFqO+7t+5WcIGvn14/JP768ad4EUQXCCxeL/DNBUJQYsI8pL5ljW/bRgEo3bYsk3BRHFg3fAr/CopGULQ+h4tgox2YxnGUhmu9cR6vVsE81dr8JIlf9MMe4ki/6tpfBkbDp7kfla3lHWTt/wsX6WNxI4jX7T8E4fKxvDZkcrvnyS8PLu5l8+gv4pdGE769wNdJHKfbb0+v10GUDWE5Mr9cfyBvf/538fPlYn13d33z+bcf7mbbzu76nFLdWhKs0oO7fvpP7H+4//T5H1/YyyL8mTCebmbF6Hz1o+dixIp7Td/KIQxWi8sMCbW1ileq8eoxfYrUFlRfN2kS/1ENLFYtjr+1uKdgoeFX/PIPQfwUpMmbOuClxowWODw24CrbkiDy0/CrzgW/IM+y6q66wsc4VD8PgYLsM8gxLroqqD6jnBK9n038nMyD4tTmSBu9MciI0RvVe0v9ZBmkRm9qrP23xmHr7IBN508HQhgXw80+1Zdtt+VWY4jrppwvPbiDz9zZyR0qW/304I5E7d4QByNxx3IxKjU9Mg53yJk7labYBcAh3OEMtbnDxFjcMS9GhfAKrTkqfejg9Fn4m8dgoe2+jqM4yTvDV3fZn2+YZYKYOuVwDWX2ZnB2B8uGIgB0YMAyiZ/X/QD7GiRp8KoNc2GZ+vdlt8AOZUOlEupJySjEmXqF7amZC7VXciYpIFIWirBJBAg9TKvTkTB5QTK7FlV9YMZ3U0Ib+d7DzPYPczZmobK4f/Tvg+hjvAnTMF6pXfdxmsZPSmbKAy6jcJntSON1Sxof/XXW2dPrMvNEvHt/E849hVl6Ha/mt1GkvIUgF0vVdLla5lcGnmCIC4g5ARBL9VcdkQl9tR9CoEaGAi45Z5RItd9P5qXQA0+NGr56CKOoKej5H9WexKlf3MhMsb2tEwqVEq/9eZhm2FJg1Q7d5G2zbSerMNMowTnVWIW5hzBGlGFMuQDYJBUU0KQR5HIs3vD9vFHSuVrkKjcbupfHMA0+qeHM9r4oGugUcYDp6CBB1EbJAKkhs9zACAtqYsTAWBCJ6SGaSVeQlCJYhAqg1lGjYTcTSl8QTAQTGHDBEdawQwR7vBM8JCcFT77TANKRNe2dEjzdUCImUMFrmP5adJp9/5yrVlps3bwWV8g33sqNlRqDX/MD1URYNhRnkqqhPjnfqs9e3IXZcNX7PgZJqAY2SIrGnjTZ2ioOsnIi9hyTTfuihP7NzTZwNfM6LwKxsCmziYy/0mXtYv/8Ofla2fMTiUJF6xalexG6J3e3cDpwdz/J+bdDcmXwaUY0xIeRHMKuqwjWeZGBHOnOG+XW+xzVty6hcpxb5pG/Ueb6yNMLOGR6gf3kcHDJ49+m5BElXMqdIoICACWGUg9lI6CsXEQJ5kJySaVoxZdcZY/qvC9NmlLChbpKPcEIMPEU42BgHSm+wDHSHYsZ5YQZBimEDFssUjXoHYR4l1GKHablwT0KKLKOHuLaVVBHbj+dmucwp7CixX7H4rhQjKTDm5raeWwPtYt6YrJXzZb8PBE1yzxCiAQIMsShEKQV0qEeaH4OtOKzWCSiCEMOpeCtpOSea4ysYjE6XRWLiKFiBVSDhQFiGAuCTH1LgWwE4bjkxMIcCCydDC/9DpnZv33Ulg4cD6zo6hxTQhJmxnv1IXpMCXN7TPd4UdsybjzlBO4cERwPJgq6YEIiw6mWWWiKPha26X2s2B92SH2NZGYdB6emvFQ40GoyOx4QDsmxyR3lw+KwoxhmJcR7HWXsGoctDzwRCw4LpBxlJpX5pnwyKHWbIXNgqQCAIYzUlNfW2q4WnK6NmIdZLQNMutV2DGayOaT1dgVeTzhO9M3Qn5wW/anuskCmW7fgwKAsAa1+YXe/A8VhSWvi59arjltR6ZCTnV6kPI40qUKYdMuV2jgwI+cuM/ikRIHgFmXlQKLQigp0O5Bja//TjYkyUVbI1g57OeYNBjBkoYCR1znEQPznw+Xrxy+Es+XV6re3j/jzL//+3aW4vu1Eb5SzvfHSxF9t1nGytb+9uZ98wbqU58osSG6/BplOs9rxAYUE2HUAyqI9DR+/ZxDAL7bmwSqX8Hb49SH/9JB696hq5bPpkSxhiX8DC9aIvh9qe0GqLeDKInXZq3sNcfbnc7ZeJB+y2SZfL3OpDsBg/ZoPWLlffVsW/0fl8UN2NK/gqg9UwOXEMM5dBA/+c7S9vmJAeWNJuT8KlSdYtKrh215Cv2x98J4DVfN93bbTr4X7/dooY/WVP/9jmZ/WIOhd/rGJxt1dIRrZTyuWM2FqUvyGy6vtcQ2h61ek1J/1UDBPnw8QNpVcVqtkqUUSY9WIUgc1906jxRWV7JPjeog7oBtE1Apk1zy212YpdcSJ2Cxq1sQtNTqjuAxbH1IVbqxkIBNXhVNb4LtLCw+rJuP5PHreZFPo96fiell4HZYclYYlx4AwlZy0RMZHi/RRh8D4WcU1BPB0VBwq4/X1UhXUokmvZZ0GOfHEKs6hyOJohSnGWDMpmkU+prFCAWkuXYDYEsAnQHqizpThtjM9mJij7y1vyq7Fbb6sbcS8aUVYd+dOGAsnsAX+4+VJ0ch5UhssQ+dJD4BF6tKNsNiHC5o0H4dGTozaYJlmPUsPsJxlBnPLwsLxsOmXK+1dpV9hc1KJ0oMq+0uw9xpbpRramzdCp5U3Iq2cJlE2gI2svYPlvFVgQ7v7HbuE2CFZ+k6noT/rgYdYK5sj+DjcPzwL5C4B2FUCTqtwALWYKocRANwWrOPy3yGZOdgqrQMkoZf+n0KPnwg5CUEaixR9PIZrGjF5IDu5/pQifd0Txm7JzP5Z/dbdAOvd7JxTsH666Hc2dLnloUoKrDlIh3DBiDlIACgIHmwCCwC8ubq+GC4H2faV3pmT7O8f4bZ/xMA+G1xKU4pxq6RrsGz02GvGrRFMCxLVcS7RyE5sTkVhAv0ZLzCv+96t2dzt2X79DjefW/nj4F1/b9UMQyU9GBFG5NQSLB2tpMGKt4P5VuI9f4tCpRoSvD+mcr9VIj/eVw1V9upfz2leSFCESbcaBFKTCz6gCC06kDLNwxt4B+y222AYKhBb2fkZpdySurJpogEWAlpBdND5e8WmgZ6jBLX1wEMUx8k68lde9k9qsxOED7pmbYv9QPnoiBrPt7OlIsulYpPgCXvYc2epVBjmTyQ0pNLy/J4ppRI6LM89i+VOsQSmWJqATiuW6CyW/cQSc4tYmlWc04rlEPnf71YsKYUXbbE0AZ1WLB0StWexbPohHJ2gWDp4nmex7OFaHl0sHZLBZ7Fs1ulKmxHrKJYDpPTtKDrkN89iuVMsS5Oxv1iOBaj1wW9/mzUsD2GyyU7y01Sh2SjSrlembBe3gPNqlmlKvXm2StJQa8R8rMOIK1rsguDgzR2r3LtP2dKQ5d6dGuNEEjHZGhQKTUoh6rWC5O96Gwt1fBvLUIkXl7LkIyfuGk905gBdaIVCAIqLfWVyqcsznLuour8C6ORWJkhoELWt0Xq9kmNvbyPX+xAHq367MsH6BEfdaKtmJIOtC3bPKLtwqHse/0Uf5RLO2oZjpg3Ha596qsc/kpGeI9H5+McKsmkf/1jS7kQE23g1x6Fv2cmMHgJolnISCHAgdX8BE09SUj+1bLTaPrvv1yM5rBD0oyiIYuWvZS7fuqHotX2NGWB/Zf5rUL5t0vrCph1zFXO1cbs1XI81E20L15I/FGg3G3uoBrVZv4tyC3T9Xk98+38=</diagram></mxfile>" > - - - - + + + + - - - - - + + + + + - - + + - - - + + + - + - + - - - - - - - - +
- default stop... - - - - - - - - - -
-
-
- - T-shape junction w/o traffic light -
-
- (Left-hand traffic) -
-
-
-
-
- T-shape junction w/o traffic light... + default stop...
- - - + + +
- occlusion + occlusion - - + + - - - - + + + + - + - - - + + + - - - + + + - - - + + + - - - + + + - - - + + + - +
- first attentio... + first attentio... - - - + + + + + + + From 880ae612bd6345dd9632d40be26d204c9152a86a Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 3 Oct 2023 17:27:16 +0900 Subject: [PATCH 8/8] fix int_occ virt_wall pos when absence_tl Signed-off-by: Mamoru Sobue --- .../src/scene_intersection.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp index cbccff29bc562..89cdeaae56723 100644 --- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp +++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp @@ -1107,9 +1107,10 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail( occlusion_stop_line_idx}; } } else { - const auto occlusion_stop_line = planner_param_.occlusion.temporal_stop_before_attention_area - ? first_attention_stop_line_idx - : occlusion_stop_line_idx; + const auto occlusion_stop_line = + (planner_param_.occlusion.temporal_stop_before_attention_area || !has_traffic_light_) + ? first_attention_stop_line_idx + : occlusion_stop_line_idx; return IntersectionModule::FirstWaitBeforeOcclusion{ is_occlusion_cleared_with_margin, closest_idx, default_stop_line_idx, occlusion_stop_line}; }