Skip to content

Commit 6903e5b

Browse files
committed
feat(intersection): more precise pass judge handling considering occlusion detection and 1st/2nd attention lane (autowarefoundation#6047)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 984e240 commit 6903e5b

File tree

7 files changed

+634
-73
lines changed

7 files changed

+634
-73
lines changed

planning/behavior_velocity_intersection_module/README.md

+59-27
Large diffs are not rendered by default.

planning/behavior_velocity_intersection_module/config/intersection.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
max_accel: -2.8
1313
max_jerk: -5.0
1414
delay_response_time: 0.5
15+
enable_pass_judge_before_default_stopline: false
1516

1617
stuck_vehicle:
1718
turn_direction:
@@ -36,7 +37,6 @@
3637
consider_wrong_direction_vehicle: false
3738
collision_detection_hold_time: 0.5
3839
min_predicted_path_confidence: 0.05
39-
keep_detection_velocity_threshold: 0.833
4040
velocity_profile:
4141
use_upstream: true
4242
minimum_upstream_velocity: 0.01

planning/behavior_velocity_intersection_module/docs/pass-judge-line.drawio.svg

+473
Loading

planning/behavior_velocity_intersection_module/src/debug.cpp

+16-4
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ visualization_msgs::msg::MarkerArray createPoseMarkerArray(
9090
marker_line.type = visualization_msgs::msg::Marker::LINE_STRIP;
9191
marker_line.action = visualization_msgs::msg::Marker::ADD;
9292
marker_line.pose.orientation = createMarkerOrientation(0, 0, 0, 1.0);
93-
marker_line.scale = createMarkerScale(0.1, 0.0, 0.0);
93+
marker_line.scale = createMarkerScale(0.2, 0.0, 0.0);
9494
marker_line.color = createMarkerColor(r, g, b, 0.999);
9595

9696
const double yaw = tf2::getYaw(pose.orientation);
@@ -283,11 +283,23 @@ visualization_msgs::msg::MarkerArray IntersectionModule::createDebugMarkerArray(
283283
&debug_marker_array, now);
284284
*/
285285

286-
if (debug_data_.pass_judge_wall_pose) {
286+
if (debug_data_.first_pass_judge_wall_pose) {
287+
const double r = debug_data_.passed_first_pass_judge ? 1.0 : 0.0;
288+
const double g = debug_data_.passed_first_pass_judge ? 0.0 : 1.0;
287289
appendMarkerArray(
288290
createPoseMarkerArray(
289-
debug_data_.pass_judge_wall_pose.value(), "pass_judge_wall_pose", module_id_, 0.7, 0.85,
290-
0.9),
291+
debug_data_.first_pass_judge_wall_pose.value(), "first_pass_judge_wall_pose", module_id_, r,
292+
g, 0.0),
293+
&debug_marker_array, now);
294+
}
295+
296+
if (debug_data_.second_pass_judge_wall_pose) {
297+
const double r = debug_data_.passed_second_pass_judge ? 1.0 : 0.0;
298+
const double g = debug_data_.passed_second_pass_judge ? 0.0 : 1.0;
299+
appendMarkerArray(
300+
createPoseMarkerArray(
301+
debug_data_.second_pass_judge_wall_pose.value(), "second_pass_judge_wall_pose", module_id_,
302+
r, g, 0.0),
291303
&debug_marker_array, now);
292304
}
293305

planning/behavior_velocity_intersection_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,8 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
6060
ip.common.max_jerk = getOrDeclareParameter<double>(node, ns + ".common.max_jerk");
6161
ip.common.delay_response_time =
6262
getOrDeclareParameter<double>(node, ns + ".common.delay_response_time");
63+
ip.common.enable_pass_judge_before_default_stopline =
64+
getOrDeclareParameter<bool>(node, ns + ".common.enable_pass_judge_before_default_stopline");
6365

6466
ip.stuck_vehicle.turn_direction.left =
6567
getOrDeclareParameter<bool>(node, ns + ".stuck_vehicle.turn_direction.left");
@@ -91,8 +93,6 @@ IntersectionModuleManager::IntersectionModuleManager(rclcpp::Node & node)
9193
getOrDeclareParameter<double>(node, ns + ".collision_detection.collision_detection_hold_time");
9294
ip.collision_detection.min_predicted_path_confidence =
9395
getOrDeclareParameter<double>(node, ns + ".collision_detection.min_predicted_path_confidence");
94-
ip.collision_detection.keep_detection_velocity_threshold = getOrDeclareParameter<double>(
95-
node, ns + ".collision_detection.keep_detection_velocity_threshold");
9696
ip.collision_detection.velocity_profile.use_upstream =
9797
getOrDeclareParameter<bool>(node, ns + ".collision_detection.velocity_profile.use_upstream");
9898
ip.collision_detection.velocity_profile.minimum_upstream_velocity = getOrDeclareParameter<double>(

planning/behavior_velocity_intersection_module/src/scene_intersection.cpp

+72-34
Original file line numberDiff line numberDiff line change
@@ -1041,7 +1041,8 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
10411041
const auto default_stopline_idx_opt = intersection_stoplines.default_stopline;
10421042
const auto first_attention_stopline_idx_opt = intersection_stoplines.first_attention_stopline;
10431043
const auto occlusion_peeking_stopline_idx_opt = intersection_stoplines.occlusion_peeking_stopline;
1044-
const auto default_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line;
1044+
const auto first_pass_judge_line_idx = intersection_stoplines.first_pass_judge_line;
1045+
const auto second_pass_judge_line_idx = intersection_stoplines.second_pass_judge_line;
10451046
const auto occlusion_wo_tl_pass_judge_line_idx =
10461047
intersection_stoplines.occlusion_wo_tl_pass_judge_line;
10471048

@@ -1221,44 +1222,76 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
12211222
prev_occlusion_status_ = occlusion_status;
12221223
}
12231224

1224-
// TODO(Mamoru Sobue): this part needs more formal handling
1225-
const size_t pass_judge_line_idx = [=]() {
1225+
const size_t pass_judge_line_idx = [&]() {
12261226
if (enable_occlusion_detection_) {
1227-
// if occlusion detection is enabled, pass_judge position is beyond the boundary of first
1228-
// attention area
12291227
if (has_traffic_light_) {
1230-
return occlusion_stopline_idx;
1228+
// if ego passed the first_pass_judge_line while it is peeking to occlusion, then its
1229+
// position is occlusion_stopline_idx. Otherwise it is first_pass_judge_line
1230+
if (passed_1st_judge_line_while_peeking_) {
1231+
return occlusion_stopline_idx;
1232+
}
1233+
const bool is_over_first_pass_judge_line =
1234+
util::isOverTargetIndex(*path, closest_idx, current_pose, first_pass_judge_line_idx);
1235+
if (is_occlusion_state && is_over_first_pass_judge_line) {
1236+
passed_1st_judge_line_while_peeking_ = true;
1237+
return occlusion_stopline_idx;
1238+
} else {
1239+
return first_pass_judge_line_idx;
1240+
}
12311241
} else if (is_occlusion_state) {
12321242
// if there is no traffic light and occlusion is detected, pass_judge position is beyond
12331243
// the boundary of first attention area
12341244
return occlusion_wo_tl_pass_judge_line_idx;
12351245
} else {
12361246
// if there is no traffic light and occlusion is not detected, pass_judge position is
12371247
// default
1238-
return default_pass_judge_line_idx;
1248+
return first_pass_judge_line_idx;
12391249
}
12401250
}
1241-
return default_pass_judge_line_idx;
1251+
return first_pass_judge_line_idx;
12421252
}();
1243-
debug_data_.pass_judge_wall_pose =
1244-
planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path);
1245-
const bool is_over_pass_judge_line =
1246-
util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx);
1247-
const double vel_norm = std::hypot(
1248-
planner_data_->current_velocity->twist.linear.x,
1249-
planner_data_->current_velocity->twist.linear.y);
1250-
const bool keep_detection =
1251-
(vel_norm < planner_param_.collision_detection.keep_detection_velocity_threshold);
1253+
12521254
const bool was_safe = std::holds_alternative<IntersectionModule::Safe>(prev_decision_result_);
1253-
// if ego is over the pass judge line and not stopped
1254-
if (is_over_default_stopline && !is_over_pass_judge_line && keep_detection) {
1255-
RCLCPP_DEBUG(logger_, "is_over_default_stopline && !is_over_pass_judge_line && keep_detection");
1256-
// do nothing
1257-
} else if (
1258-
(was_safe && is_over_default_stopline && is_over_pass_judge_line && is_go_out_) ||
1255+
1256+
const bool is_over_1st_pass_judge_line =
1257+
util::isOverTargetIndex(*path, closest_idx, current_pose, pass_judge_line_idx);
1258+
if (is_over_1st_pass_judge_line && was_safe && !safely_passed_1st_judge_line_time_) {
1259+
safely_passed_1st_judge_line_time_ = clock_->now();
1260+
}
1261+
debug_data_.first_pass_judge_wall_pose =
1262+
planning_utils::getAheadPose(pass_judge_line_idx, baselink2front, *path);
1263+
debug_data_.passed_first_pass_judge = safely_passed_1st_judge_line_time_.has_value();
1264+
const bool is_over_2nd_pass_judge_line =
1265+
util::isOverTargetIndex(*path, closest_idx, current_pose, second_pass_judge_line_idx);
1266+
if (is_over_2nd_pass_judge_line && was_safe && !safely_passed_2nd_judge_line_time_) {
1267+
safely_passed_2nd_judge_line_time_ = clock_->now();
1268+
}
1269+
debug_data_.second_pass_judge_wall_pose =
1270+
planning_utils::getAheadPose(second_pass_judge_line_idx, baselink2front, *path);
1271+
debug_data_.passed_second_pass_judge = safely_passed_2nd_judge_line_time_.has_value();
1272+
1273+
if (
1274+
((is_over_default_stopline ||
1275+
planner_param_.common.enable_pass_judge_before_default_stopline) &&
1276+
is_over_2nd_pass_judge_line && was_safe) ||
12591277
is_permanent_go_) {
1260-
// is_go_out_: previous RTC approval
1261-
// activated_: current RTC approval
1278+
/*
1279+
* This body is active if ego is
1280+
* - over the default stopline AND
1281+
* - over the 1st && 2nd pass judge line AND
1282+
* - previously safe
1283+
* ,
1284+
* which means ego can stop even if it is over the 1st pass judge line but
1285+
* - before default stopline OR
1286+
* - before the 2nd pass judge line OR
1287+
* - or previously unsafe
1288+
* .
1289+
* In order for ego to continue peeking or collision detection when occlusion is detected after
1290+
* ego passed the 1st pass judge line, it needs to be
1291+
* - before the default stopline OR
1292+
* - before the 2nd pass judge line OR
1293+
* - previously unsafe
1294+
*/
12621295
is_permanent_go_ = true;
12631296
return IntersectionModule::Indecisive{"over the pass judge line. no plan needed"};
12641297
}
@@ -1309,10 +1342,14 @@ IntersectionModule::DecisionResult IntersectionModule::modifyPathVelocityDetail(
13091342
: (planner_param_.collision_detection.collision_detection_hold_time -
13101343
collision_state_machine_.getDuration());
13111344

1345+
// TODO(Mamoru Sobue): if ego is over 1st/2nd pass judge line and collision is expected at 1st/2nd
1346+
// pass judge line respectively, ego should go
1347+
const auto second_attention_stopline_idx = intersection_stoplines.second_attention_stopline;
1348+
const auto last_intersection_stopline_candidate_idx =
1349+
second_attention_stopline_idx ? second_attention_stopline_idx.value() : occlusion_stopline_idx;
13121350
const bool has_collision = checkCollision(
1313-
*path, &target_objects, path_lanelets, closest_idx,
1314-
std::min<size_t>(occlusion_stopline_idx, path->points.size() - 1), time_to_restart,
1315-
traffic_prioritized_level);
1351+
*path, &target_objects, path_lanelets, closest_idx, last_intersection_stopline_candidate_idx,
1352+
time_to_restart, traffic_prioritized_level);
13161353
collision_state_machine_.setStateWithMarginTime(
13171354
has_collision ? StateMachine::State::STOP : StateMachine::State::GO,
13181355
logger_.get_child("collision state_machine"), *clock_);
@@ -1808,16 +1845,19 @@ std::optional<IntersectionStopLines> IntersectionModule::generateIntersectionSto
18081845
second_attention_area, interpolated_path_info, local_footprint, baselink2front);
18091846
if (first_footprint_inside_2nd_attention_ip_opt) {
18101847
second_attention_stopline_ip_int = first_footprint_inside_2nd_attention_ip_opt.value();
1848+
second_attention_stopline_valid = true;
18111849
}
18121850
}
18131851
const auto second_attention_stopline_ip =
18141852
second_attention_stopline_ip_int >= 0 ? static_cast<size_t>(second_attention_stopline_ip_int)
18151853
: 0;
18161854

1817-
// (8) second pass judge lie position on interpolated path
1818-
int second_pass_judge_ip_int = second_attention_stopline_ip_int - std::ceil(braking_dist / ds);
1855+
// (8) second pass judge line position on interpolated path. It is the same as first pass judge
1856+
// line if second_attention_lane is null
1857+
int second_pass_judge_ip_int = occlusion_wo_tl_pass_judge_line_ip;
18191858
const auto second_pass_judge_line_ip =
1820-
static_cast<size_t>(std::max<int>(second_pass_judge_ip_int, 0));
1859+
second_attention_area_opt ? static_cast<size_t>(std::max<int>(second_pass_judge_ip_int, 0))
1860+
: first_pass_judge_line_ip;
18211861

18221862
struct IntersectionStopLinesTemp
18231863
{
@@ -2803,8 +2843,6 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime(
28032843
return std::nullopt;
28042844
}
28052845
}();
2806-
const bool has_upstream_stopline = upstream_stopline_idx_opt.has_value();
2807-
const size_t upstream_stopline_ind = upstream_stopline_idx_opt.value_or(0);
28082846

28092847
for (size_t i = smoothed_path_closest_idx; i < smoothed_reference_path.points.size() - 1; ++i) {
28102848
const auto & p1 = smoothed_reference_path.points.at(i);
@@ -2818,7 +2856,7 @@ TimeDistanceArray IntersectionModule::calcIntersectionPassingTime(
28182856
(p1.point.longitudinal_velocity_mps + p2.point.longitudinal_velocity_mps) / 2.0;
28192857
const double passing_velocity = [=]() {
28202858
if (use_upstream_velocity) {
2821-
if (has_upstream_stopline && i > upstream_stopline_ind) {
2859+
if (upstream_stopline_idx_opt && i > upstream_stopline_idx_opt.value()) {
28222860
return minimum_upstream_velocity;
28232861
}
28242862
return std::max<double>(average_velocity, minimum_ego_velocity);

planning/behavior_velocity_intersection_module/src/scene_intersection.hpp

+11-5
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,10 @@ struct DebugData
4848
std::optional<geometry_msgs::msg::Pose> collision_stop_wall_pose{std::nullopt};
4949
std::optional<geometry_msgs::msg::Pose> occlusion_stop_wall_pose{std::nullopt};
5050
std::optional<geometry_msgs::msg::Pose> occlusion_first_stop_wall_pose{std::nullopt};
51-
std::optional<geometry_msgs::msg::Pose> pass_judge_wall_pose{std::nullopt};
51+
std::optional<geometry_msgs::msg::Pose> first_pass_judge_wall_pose{std::nullopt};
52+
bool passed_first_pass_judge{false};
53+
bool passed_second_pass_judge{false};
54+
std::optional<geometry_msgs::msg::Pose> second_pass_judge_wall_pose{std::nullopt};
5255
std::optional<std::vector<lanelet::CompoundPolygon3d>> attention_area{std::nullopt};
5356
std::optional<std::vector<lanelet::CompoundPolygon3d>> occlusion_attention_area{std::nullopt};
5457
std::optional<lanelet::CompoundPolygon3d> ego_lane{std::nullopt};
@@ -256,8 +259,8 @@ struct IntersectionStopLines
256259
size_t first_pass_judge_line{0};
257260

258261
/**
259-
* second_pass_judge_line is before second_attention_stopline by the braking distance. if its
260-
* value is calculated negative, it is 0
262+
* second_pass_judge_line is before second_attention_stopline by the braking distance. if
263+
* second_attention_lane is null, it is same as first_pass_judge_line
261264
*/
262265
size_t second_pass_judge_line{0};
263266

@@ -344,6 +347,7 @@ class IntersectionModule : public SceneModuleInterface
344347
double max_accel;
345348
double max_jerk;
346349
double delay_response_time;
350+
bool enable_pass_judge_before_default_stopline;
347351
} common;
348352

349353
struct TurnDirection
@@ -373,7 +377,6 @@ class IntersectionModule : public SceneModuleInterface
373377
bool consider_wrong_direction_vehicle;
374378
double collision_detection_hold_time;
375379
double min_predicted_path_confidence;
376-
double keep_detection_velocity_threshold;
377380
struct VelocityProfile
378381
{
379382
bool use_upstream;
@@ -606,7 +609,7 @@ class IntersectionModule : public SceneModuleInterface
606609

607610
private:
608611
rclcpp::Node & node_;
609-
const int64_t lane_id_;
612+
const lanelet::Id lane_id_;
610613
const std::set<lanelet::Id> associative_ids_;
611614
const std::string turn_direction_;
612615
const bool has_traffic_light_;
@@ -621,6 +624,9 @@ class IntersectionModule : public SceneModuleInterface
621624
bool is_permanent_go_{false};
622625
DecisionResult prev_decision_result_{Indecisive{""}};
623626
OcclusionType prev_occlusion_status_;
627+
bool passed_1st_judge_line_while_peeking_{false};
628+
std::optional<rclcpp::Time> safely_passed_1st_judge_line_time_{std::nullopt};
629+
std::optional<rclcpp::Time> safely_passed_2nd_judge_line_time_{std::nullopt};
624630

625631
// for occlusion detection
626632
const bool enable_occlusion_detection_;

0 commit comments

Comments
 (0)