diff --git a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
index 266ab5a581b3a..f950e5853c4be 100644
--- a/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
+++ b/planning/behavior_velocity_intersection_module/config/intersection.param.yaml
@@ -34,6 +34,8 @@
collision_start_margin_time: 4.0 # [s] this + state_transit_margin_time should be higher to account for collision with fast/accelerating object
collision_end_margin_time: 6.0 # [s] this + state_transit_margin_time should be higher to account for collision with slow/decelerating object
keep_detection_vel_thr: 0.833 # == 3.0km/h. keep detection if ego is ego.vel < keep_detection_vel_thr
+ use_upstream_velocity: true # flag to use the planned velocity profile from the upstream module
+ minimum_upstream_velocity: 0.01 # [m/s] minimum velocity to avoid null division for the stop line from the upstream velocity
occlusion:
enable: false
diff --git a/planning/behavior_velocity_intersection_module/package.xml b/planning/behavior_velocity_intersection_module/package.xml
index 1cbecb636b457..0c9b3407d0f38 100644
--- a/planning/behavior_velocity_intersection_module/package.xml
+++ b/planning/behavior_velocity_intersection_module/package.xml
@@ -9,6 +9,7 @@
Takayuki Murooka
Tomoya Kimura
Shumpei Wakabayashi
+ Kyoichi Sugahara
Apache License 2.0
diff --git a/planning/behavior_velocity_intersection_module/src/manager.cpp b/planning/behavior_velocity_intersection_module/src/manager.cpp
index c2761e2cefb86..f2f0951d65357 100644
--- a/planning/behavior_velocity_intersection_module/src/manager.cpp
+++ b/planning/behavior_velocity_intersection_module/src/manager.cpp
@@ -100,6 +100,10 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
ns + ".collision_detection.not_prioritized.collision_end_margin_time");
ip.collision_detection.keep_detection_vel_thr =
node.declare_parameter(ns + ".collision_detection.keep_detection_vel_thr");
+ ip.collision_detection.use_upstream_velocity =
+ node.declare_parameter(ns + ".collision_detection.use_upstream_velocity");
+ ip.collision_detection.minimum_upstream_velocity =
+ node.declare_parameter(ns + ".collision_detection.minimum_upstream_velocity");
ip.occlusion.enable = node.declare_parameter(ns + ".occlusion.enable");
ip.occlusion.occlusion_attention_area_length =
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
index 1be9bdf311ea6..5f9461546bd2d 100644
--- a/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
+++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.cpp
@@ -1081,7 +1081,9 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
collision_state_machine_.getDuration());
const bool has_collision = checkCollision(
- *path, &target_objects, path_lanelets, closest_idx, time_to_restart, traffic_prioritized_level);
+ *path, &target_objects, path_lanelets, closest_idx,
+ 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,
logger_.get_child("collision state_machine"), *clock_);
@@ -1281,8 +1283,8 @@ util::TargetObjects IntersectionModule::generateTargetObjects(
bool IntersectionModule::checkCollision(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets,
- const int closest_idx, const double time_delay,
- const util::TrafficPrioritizedLevel & traffic_prioritized_level)
+ const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx,
+ const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level)
{
using lanelet::utils::getArcCoordinates;
using lanelet::utils::getPolygonFromArcLength;
@@ -1290,9 +1292,11 @@ bool IntersectionModule::checkCollision(
// check collision between target_objects predicted path and ego lane
// cut the predicted path at passing_time
const auto time_distance_array = util::calcIntersectionPassingTime(
- path, planner_data_, associative_ids_, closest_idx, time_delay,
- planner_param_.common.intersection_velocity,
- planner_param_.collision_detection.minimum_ego_predicted_velocity);
+ path, planner_data_, associative_ids_, closest_idx, last_intersection_stop_line_candidate_idx,
+ time_delay, planner_param_.common.intersection_velocity,
+ planner_param_.collision_detection.minimum_ego_predicted_velocity,
+ planner_param_.collision_detection.use_upstream_velocity,
+ planner_param_.collision_detection.minimum_upstream_velocity);
const double passing_time = time_distance_array.back().first;
util::cutPredictPathWithDuration(target_objects, clock_, passing_time);
diff --git a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
index ecd9ccf877965..8c09636678a01 100644
--- a/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
+++ b/planning/behavior_velocity_intersection_module/src/scene_intersection.hpp
@@ -94,6 +94,8 @@ class IntersectionModule : public SceneModuleInterface
double collision_end_margin_time; //! end margin time to check collision
} not_prioritized;
double keep_detection_vel_thr; //! keep detection if ego is ego.vel < keep_detection_vel_thr
+ bool use_upstream_velocity;
+ double minimum_upstream_velocity;
} collision_detection;
struct Occlusion
{
@@ -300,8 +302,8 @@ class IntersectionModule : public SceneModuleInterface
bool checkCollision(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
util::TargetObjects * target_objects, const util::PathLanelets & path_lanelets,
- const int closest_idx, const double time_delay,
- const util::TrafficPrioritizedLevel & traffic_prioritized_level);
+ const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx,
+ const double time_delay, const util::TrafficPrioritizedLevel & traffic_prioritized_level);
OcclusionType getOcclusionStatus(
const nav_msgs::msg::OccupancyGrid & occ_grid,
diff --git a/planning/behavior_velocity_intersection_module/src/util.cpp b/planning/behavior_velocity_intersection_module/src/util.cpp
index 8f2889726d365..3a3d84258f7de 100644
--- a/planning/behavior_velocity_intersection_module/src/util.cpp
+++ b/planning/behavior_velocity_intersection_module/src/util.cpp
@@ -1273,8 +1273,9 @@ void cutPredictPathWithDuration(
TimeDistanceArray calcIntersectionPassingTime(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const std::shared_ptr & planner_data, const std::set & associative_ids,
- const int closest_idx, const double time_delay, const double intersection_velocity,
- const double minimum_ego_velocity)
+ const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx,
+ const double time_delay, const double intersection_velocity, const double minimum_ego_velocity,
+ const bool use_upstream_velocity, const double minimum_upstream_velocity)
{
double dist_sum = 0.0;
int assigned_lane_found = false;
@@ -1284,7 +1285,9 @@ TimeDistanceArray calcIntersectionPassingTime(
PathWithLaneId reference_path;
for (size_t i = closest_idx; i < path.points.size(); ++i) {
auto reference_point = path.points.at(i);
- reference_point.point.longitudinal_velocity_mps = intersection_velocity;
+ if (!use_upstream_velocity) {
+ reference_point.point.longitudinal_velocity_mps = intersection_velocity;
+ }
reference_path.points.push_back(reference_point);
bool has_objective_lane_id = hasLaneIds(path.points.at(i), associative_ids);
if (assigned_lane_found && !has_objective_lane_id) {
@@ -1315,10 +1318,13 @@ TimeDistanceArray calcIntersectionPassingTime(
// use average velocity between p1 and p2
const double average_velocity =
(p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0;
- passing_time +=
- (dist / std::max(
- minimum_ego_velocity,
- average_velocity)); // to avoid zero-division
+ const double minimum_ego_velocity_division =
+ (use_upstream_velocity && i > last_intersection_stop_line_candidate_idx)
+ ? minimum_upstream_velocity /* to avoid null division */
+ : minimum_ego_velocity;
+ const double passing_velocity =
+ std::max(minimum_ego_velocity_division, average_velocity);
+ passing_time += (dist / passing_velocity);
time_distance_array.emplace_back(passing_time, dist_sum);
}
diff --git a/planning/behavior_velocity_intersection_module/src/util.hpp b/planning/behavior_velocity_intersection_module/src/util.hpp
index e7ba2b00c749a..d1daf2a6e9114 100644
--- a/planning/behavior_velocity_intersection_module/src/util.hpp
+++ b/planning/behavior_velocity_intersection_module/src/util.hpp
@@ -141,8 +141,9 @@ void cutPredictPathWithDuration(
TimeDistanceArray calcIntersectionPassingTime(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const std::shared_ptr & planner_data, const std::set & associative_ids,
- const int closest_idx, const double time_delay, const double intersection_velocity,
- const double minimum_ego_velocity);
+ const size_t closest_idx, const size_t last_intersection_stop_line_candidate_idx,
+ const double time_delay, const double intersection_velocity, const double minimum_ego_velocity,
+ const bool use_upstream_velocity, const double minimum_upstream_velocity);
double calcDistanceUntilIntersectionLanelet(
const lanelet::ConstLanelet & assigned_lanelet,