Skip to content

Commit 08f108d

Browse files
committed
feat(behavior_velocity_blind_spot): use TTC for object in detection_area (autowarefoundation#7146)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent ba48569 commit 08f108d

File tree

5 files changed

+170
-214
lines changed

5 files changed

+170
-214
lines changed

planning/behavior_velocity_blind_spot_module/config/blind_spot.param.yaml

+5-3
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,12 @@
33
blind_spot:
44
use_pass_judge_line: true
55
stop_line_margin: 1.0 # [m]
6-
backward_length: 50.0 # [m]
6+
backward_detection_length: 100.0 # [m]
77
ignore_width_from_center_line: 0.7 # [m]
8-
max_future_movement_time: 10.0 # [second]
9-
threshold_yaw_diff: 0.523 # [rad]
108
adjacent_extend_width: 1.5 # [m]
119
opposite_adjacent_extend_width: 1.5 # [m]
10+
max_future_movement_time: 10.0 # [second]
11+
ttc_min: -5.0 # [s]
12+
ttc_max: 5.0 # [s]
13+
ttc_ego_minimal_velocity: 5.0 # [m/s]
1214
enable_rtc: false # 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

planning/behavior_velocity_blind_spot_module/src/debug.cpp

+6-9
Original file line numberDiff line numberDiff line change
@@ -93,15 +93,12 @@ visualization_msgs::msg::MarkerArray BlindSpotModule::createDebugMarkerArray()
9393

9494
const auto now = this->clock_->now();
9595

96-
appendMarkerArray(
97-
createLaneletPolygonsMarkerArray(
98-
debug_data_.conflict_areas, "conflict_area", module_id_, 0.0, 0.5, 0.5),
99-
&debug_marker_array, now);
100-
101-
appendMarkerArray(
102-
createLaneletPolygonsMarkerArray(
103-
debug_data_.detection_areas, "detection_area", module_id_, 0.5, 0.0, 0.0),
104-
&debug_marker_array, now);
96+
if (debug_data_.detection_area) {
97+
appendMarkerArray(
98+
createLaneletPolygonsMarkerArray(
99+
{debug_data_.detection_area.value()}, "detection_area", module_id_, 0.5, 0.0, 0.0),
100+
&debug_marker_array, now);
101+
}
105102

106103
appendMarkerArray(
107104
debug::createObjectsMarkerArray(

planning/behavior_velocity_blind_spot_module/src/manager.cpp

+8-5
Original file line numberDiff line numberDiff line change
@@ -36,17 +36,20 @@ BlindSpotModuleManager::BlindSpotModuleManager(rclcpp::Node & node)
3636
planner_param_.use_pass_judge_line =
3737
getOrDeclareParameter<bool>(node, ns + ".use_pass_judge_line");
3838
planner_param_.stop_line_margin = getOrDeclareParameter<double>(node, ns + ".stop_line_margin");
39-
planner_param_.backward_length = getOrDeclareParameter<double>(node, ns + ".backward_length");
39+
planner_param_.backward_detection_length =
40+
getOrDeclareParameter<double>(node, ns + ".backward_detection_length");
4041
planner_param_.ignore_width_from_center_line =
4142
getOrDeclareParameter<double>(node, ns + ".ignore_width_from_center_line");
42-
planner_param_.max_future_movement_time =
43-
getOrDeclareParameter<double>(node, ns + ".max_future_movement_time");
44-
planner_param_.threshold_yaw_diff =
45-
getOrDeclareParameter<double>(node, ns + ".threshold_yaw_diff");
4643
planner_param_.adjacent_extend_width =
4744
getOrDeclareParameter<double>(node, ns + ".adjacent_extend_width");
4845
planner_param_.opposite_adjacent_extend_width =
4946
getOrDeclareParameter<double>(node, ns + ".opposite_adjacent_extend_width");
47+
planner_param_.max_future_movement_time =
48+
getOrDeclareParameter<double>(node, ns + ".max_future_movement_time");
49+
planner_param_.ttc_min = getOrDeclareParameter<double>(node, ns + ".ttc_min");
50+
planner_param_.ttc_max = getOrDeclareParameter<double>(node, ns + ".ttc_max");
51+
planner_param_.ttc_ego_minimal_velocity =
52+
getOrDeclareParameter<double>(node, ns + ".ttc_ego_minimal_velocity");
5053
}
5154

5255
void BlindSpotModuleManager::launchNewModules(

0 commit comments

Comments
 (0)