Skip to content

Commit

Permalink
Merge pull request #891 from tier4/hotfix/pr5156-2
Browse files Browse the repository at this point in the history
feat(intersection): use planned velocity from upstream modules (autowarefoundation#5156)
  • Loading branch information
takayuki5168 authored Sep 30, 2023
2 parents 5fdd247 + 69466aa commit 31d6c16
Show file tree
Hide file tree
Showing 7 changed files with 34 additions and 15 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@
collision_start_margin_time: 2.0
collision_end_margin_time: 0.0
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
Expand Down
1 change: 1 addition & 0 deletions planning/behavior_velocity_intersection_module/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@
<maintainer email="[email protected]">Takayuki Murooka</maintainer>
<maintainer email="[email protected]">Tomoya Kimura</maintainer>
<maintainer email="[email protected]">Shumpei Wakabayashi</maintainer>
<maintainer email="[email protected]">Kyoichi Sugahara</maintainer>

<license>Apache License 2.0</license>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,10 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
node, ns + ".collision_detection.relaxed.collision_end_margin_time");
ip.collision_detection.keep_detection_vel_thr =
getOrDeclareParameter<double>(node, ns + ".collision_detection.keep_detection_vel_thr");
ip.collision_detection.use_upstream_velocity =
getOrDeclareParameter<bool>(node, ns + ".collision_detection.use_upstream_velocity");
ip.collision_detection.minimum_upstream_velocity =
getOrDeclareParameter<double>(node, ns + ".collision_detection.minimum_upstream_velocity");

ip.occlusion.enable = getOrDeclareParameter<bool>(node, ns + ".occlusion.enable");
ip.occlusion.occlusion_attention_area_length =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -875,7 +875,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
filterTargetObjects(attention_lanelets, adjacent_lanelets, intersection_area);

const bool has_collision = checkCollision(
*path, target_objects, path_lanelets, closest_idx, time_delay, tl_arrow_solid_on);
*path, target_objects, path_lanelets, closest_idx, time_delay,
std::min<size_t>(occlusion_peeking_stop_line_idx, path->points.size() - 1), tl_arrow_solid_on);
collision_state_machine_.setStateWithMarginTime(
has_collision ? StateMachine::State::STOP : StateMachine::State::GO,
logger_.get_child("collision state_machine"), *clock_);
Expand Down Expand Up @@ -1060,17 +1061,19 @@ bool IntersectionModule::checkCollision(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const autoware_auto_perception_msgs::msg::PredictedObjects & objects,
const util::PathLanelets & path_lanelets, const int closest_idx, const double time_delay,
const bool tl_arrow_solid_on)
const size_t last_intersection_stop_line_candidate_idx, const bool tl_arrow_solid_on)
{
using lanelet::utils::getArcCoordinates;
using lanelet::utils::getPolygonFromArcLength;

// 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;
auto target_objects = objects;
util::cutPredictPathWithDuration(&target_objects, clock_, passing_time);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,8 @@ class IntersectionModule : public SceneModuleInterface
double collision_end_margin_time;
} relaxed;
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
{
Expand Down Expand Up @@ -261,7 +263,7 @@ class IntersectionModule : public SceneModuleInterface
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const autoware_auto_perception_msgs::msg::PredictedObjects & target_objects,
const util::PathLanelets & path_lanelets, const int closest_idx, const double time_delay,
const bool tl_arrow_solid_on);
const size_t last_intersection_stop_line_candidate_idx, const bool tl_arrow_solid_on);

bool isOcclusionCleared(
const nav_msgs::msg::OccupancyGrid & occ_grid,
Expand Down
20 changes: 13 additions & 7 deletions planning/behavior_velocity_intersection_module/src/util.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1012,8 +1012,9 @@ void cutPredictPathWithDuration(
TimeDistanceArray calcIntersectionPassingTime(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data, const std::set<int> & 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;
Expand All @@ -1023,7 +1024,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) {
Expand Down Expand Up @@ -1054,10 +1057,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<double>(
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<double>(minimum_ego_velocity_division, average_velocity);
passing_time += (dist / passing_velocity);

time_distance_array.emplace_back(passing_time, dist_sum);
}
Expand Down
5 changes: 3 additions & 2 deletions planning/behavior_velocity_intersection_module/src/util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,9 @@ void cutPredictPathWithDuration(
TimeDistanceArray calcIntersectionPassingTime(
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const std::shared_ptr<const PlannerData> & planner_data, const std::set<int> & 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,
Expand Down

0 comments on commit 31d6c16

Please sign in to comment.