Skip to content

Commit 031c873

Browse files
authored
feat(crosswalk): ignore occlusions in the presence of traffic lights (#6604)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 52efb84 commit 031c873

File tree

7 files changed

+12
-7
lines changed

7 files changed

+12
-7
lines changed

planning/behavior_velocity_crosswalk_module/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -209,7 +209,7 @@ This range is meant to be large when ego is far from the crosswalk and small whe
209209
In order to avoid flickering decisions, a time buffer can be used such that the decision to add (or remove) the slow down is only taken
210210
after an occlusion is detected (or not detected) for a consecutive time defined by the `time_buffer` parameter.
211211

212-
To ignore occlusions when the pedestrian light is red, `ignore_with_red_traffic_light` should be set to true.
212+
To ignore occlusions when the crosswalk has a traffic light, `ignore_with_traffic_light` should be set to true.
213213

214214
To ignore temporary occlusions caused by moving objects,
215215
`ignore_behind_predicted_objects` should be set to true.
@@ -230,7 +230,7 @@ To inflate the masking behind objects, their footprint can be made bigger using
230230
| `min_size` | [m] | double | minimum size of an occlusion (square side size) |
231231
| `free_space_max` | [-] | double | maximum value of a free space cell in the occupancy grid |
232232
| `occupied_min` | [-] | double | minimum value of an occupied cell in the occupancy grid |
233-
| `ignore_with_red_traffic_light` | [-] | bool | if true, occlusions at crosswalks with traffic lights are ignored |
233+
| `ignore_with_traffic_light` | [-] | bool | if true, occlusions at crosswalks with traffic lights are ignored |
234234
| `ignore_behind_predicted_objects` | [-] | bool | if true, occlusions behind predicted objects are ignored |
235235
| `ignore_velocity_thresholds.default` | [m/s] | double | occlusions are only ignored behind objects with a higher or equal velocity |
236236
| `ignore_velocity_thresholds.custom_labels` | [-] | string list | labels for which to define a non-default velocity threshold (see `autoware_auto_perception_msgs::msg::ObjectClassification` for all the labels) |

planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@
7878
min_size: 0.5 # [m] minimum size of an occlusion (square side size)
7979
free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid
8080
occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid
81-
ignore_with_red_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored
81+
ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored
8282
ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored
8383
ignore_velocity_thresholds:
8484
default: 0.5 # [m/s] occlusions are only ignored behind objects with a higher or equal velocity

planning/behavior_velocity_crosswalk_module/include/behavior_velocity_crosswalk_module/util.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@ struct DebugData
6767
bool ignore_crosswalk{false};
6868
double base_link2front;
6969
double stop_judge_range{};
70+
std::string virtual_wall_suffix{};
7071

7172
geometry_msgs::msg::Pose first_stop_pose;
7273
geometry_msgs::msg::Point nearest_collision_point;

planning/behavior_velocity_crosswalk_module/src/debug.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -190,6 +190,7 @@ motion_utils::VirtualWalls CrosswalkModule::createVirtualWalls()
190190
virtual_walls.push_back(wall);
191191
}
192192
wall.style = motion_utils::VirtualWallType::slowdown;
193+
wall.text += debug_data_.virtual_wall_suffix;
193194
for (const auto & p : debug_data_.slow_poses) {
194195
wall.pose = calcOffsetPose(p, debug_data_.base_link2front, 0.0, 0.0);
195196
virtual_walls.push_back(wall);

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -135,8 +135,8 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
135135
cp.occlusion_min_size = getOrDeclareParameter<double>(node, ns + ".occlusion.min_size");
136136
cp.occlusion_free_space_max = getOrDeclareParameter<int>(node, ns + ".occlusion.free_space_max");
137137
cp.occlusion_occupied_min = getOrDeclareParameter<int>(node, ns + ".occlusion.occupied_min");
138-
cp.occlusion_ignore_with_red_traffic_light =
139-
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_red_traffic_light");
138+
cp.occlusion_ignore_with_traffic_light =
139+
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
140140
cp.occlusion_ignore_behind_predicted_objects =
141141
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
142142

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -240,8 +240,10 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
240240
const auto cmp_with_time_buffer = [&](const auto & t, const auto cmp_fn) {
241241
return t && cmp_fn((now - *t).seconds(), planner_param_.occlusion_time_buffer);
242242
};
243+
const auto crosswalk_has_traffic_light =
244+
!crosswalk_.regulatoryElementsAs<const lanelet::TrafficLight>().empty();
243245
const auto is_crosswalk_ignored =
244-
(planner_param_.occlusion_ignore_with_red_traffic_light && isRedSignalForPedestrians()) ||
246+
(planner_param_.occlusion_ignore_with_traffic_light && crosswalk_has_traffic_light) ||
245247
crosswalk_.hasAttribute("skip_occluded_slowdown");
246248
if (planner_param_.occlusion_enable && !path_intersects.empty() && !is_crosswalk_ignored) {
247249
const auto dist_ego_to_crosswalk =
@@ -269,6 +271,7 @@ bool CrosswalkModule::modifyPathVelocity(PathWithLaneId * path, StopReason * sto
269271
applySafetySlowDownSpeed(
270272
*path, path_intersects,
271273
std::max(target_velocity, planner_param_.occlusion_slow_down_velocity));
274+
debug_data_.virtual_wall_suffix = " (occluded)";
272275
} else {
273276
most_recent_occlusion_time_.reset();
274277
}

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -162,7 +162,7 @@ class CrosswalkModule : public SceneModuleInterface
162162
double occlusion_min_size;
163163
int occlusion_free_space_max;
164164
int occlusion_occupied_min;
165-
bool occlusion_ignore_with_red_traffic_light;
165+
bool occlusion_ignore_with_traffic_light;
166166
bool occlusion_ignore_behind_predicted_objects;
167167
std::vector<double> occlusion_ignore_velocity_thresholds;
168168
double occlusion_extra_objects_size;

0 commit comments

Comments
 (0)