Skip to content

Commit e4189e2

Browse files
committed
Refactor and add param to NOT ignore behind pedestrians
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 4d0709b commit e4189e2

File tree

5 files changed

+56
-16
lines changed

5 files changed

+56
-16
lines changed

planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -81,5 +81,6 @@
8181
occupied_min: 58 # [-] minimum value of an occupied cell in the occupancy grid
8282
ignore_with_traffic_light: true # [-] if true, occlusions at crosswalks with traffic lights are ignored
8383
ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored
84+
do_not_ignore_behind_pedestrians: true # [-] if true, occlusions behind pedestrians are not ignored
8485
min_objects_velocity: 0.5 # [m/s] minimum velocity for a predicted object to be ignored
8586
extra_objects_size: 0.5 # [m] extra size added to the objects when masking the occlusions

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -140,10 +140,12 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
140140
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_with_traffic_light");
141141
cp.occlusion_ignore_behind_predicted_objects =
142142
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
143-
cp.occlusion_min_objects_velocity =
144-
getOrDeclareParameter<double>(node, ns + ".occlusion.min_objects_velocity");
143+
cp.occlusion_do_not_ignore_behind_pedestrians =
144+
getOrDeclareParameter<bool>(node, ns + ".occlusion.do_not_ignore_behind_pedestrians");
145+
cp.occlusion_ignore_velocity_threshold =
146+
getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_threshold");
145147
cp.occlusion_extra_objects_size =
146-
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_objects_size");
148+
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_predicted_objects_size");
147149
}
148150

149151
void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.cpp

+30-12
Original file line numberDiff line numberDiff line change
@@ -94,10 +94,30 @@ std::vector<lanelet::BasicPolygon2d> calculate_detection_areas(
9494
return detection_areas;
9595
}
9696

97-
void clear_behind_objects(
98-
grid_map::GridMap & grid_map,
97+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
9998
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
100-
const double min_object_velocity, const double extra_object_size)
99+
const double velocity_threshold, const bool skip_pedestrians, const double inflate_size)
100+
{
101+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> selected_objects;
102+
for (const auto & o : objects) {
103+
const auto skip =
104+
(skip_pedestrians &&
105+
o.classification.front().label ==
106+
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN) ||
107+
o.kinematics.initial_twist_with_covariance.twist.linear.x >= velocity_threshold;
108+
if (!skip) {
109+
auto selected_object = o;
110+
selected_object.shape.dimensions.x += inflate_size;
111+
selected_object.shape.dimensions.y += inflate_size;
112+
selected_objects.push_back(selected_object);
113+
}
114+
}
115+
return selected_objects;
116+
}
117+
118+
void clear_occlusions_behind_objects(
119+
grid_map::GridMap & grid_map,
120+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects)
101121
{
102122
const auto angle_cmp = [&](const auto & p1, const auto & p2) {
103123
const auto d1 = p1 - grid_map.getPosition();
@@ -107,14 +127,10 @@ void clear_behind_objects(
107127
const lanelet::BasicPoint2d grid_map_position = grid_map.getPosition();
108128
const auto range = grid_map.getLength().maxCoeff() / 2.0;
109129
for (auto object : objects) {
110-
object.shape.dimensions.x += extra_object_size;
111-
object.shape.dimensions.y += extra_object_size;
112130
const lanelet::BasicPoint2d object_position = {
113131
object.kinematics.initial_pose_with_covariance.pose.position.x,
114132
object.kinematics.initial_pose_with_covariance.pose.position.y};
115-
if (
116-
object.kinematics.initial_twist_with_covariance.twist.linear.x >= min_object_velocity &&
117-
lanelet::geometry::distance2d(grid_map_position, object_position) < range) {
133+
if (lanelet::geometry::distance2d(grid_map_position, object_position) < range) {
118134
lanelet::BasicPoints2d edge_points;
119135
const auto object_polygon = tier4_autoware_utils::toPolygon2d(object);
120136
for (const auto & edge_point : object_polygon.outer()) edge_points.push_back(edge_point);
@@ -143,10 +159,12 @@ bool is_crosswalk_occluded(
143159
grid_map::GridMap grid_map;
144160
grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map);
145161

146-
if (params.occlusion_ignore_behind_predicted_objects)
147-
clear_behind_objects(
148-
grid_map, dynamic_objects, params.occlusion_min_objects_velocity,
149-
params.occlusion_extra_objects_size);
162+
if (params.occlusion_ignore_behind_predicted_objects) {
163+
const auto objects = select_and_inflate_objects(
164+
dynamic_objects, params.occlusion_ignore_velocity_threshold,
165+
params.occlusion_do_not_ignore_behind_pedestrians, params.occlusion_extra_objects_size);
166+
clear_occlusions_behind_objects(grid_map, objects);
167+
}
150168
const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution());
151169
for (const auto & detection_area : calculate_detection_areas(
152170
crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {

planning/behavior_velocity_crosswalk_module/src/occluded_crosswalk.hpp

+18
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,24 @@ double calculate_detection_range(
7979
const double occluded_object_velocity, const double dist_ego_to_crosswalk,
8080
const double ego_velocity);
8181

82+
/// @brief select a subset of objects meeting the velocity threshold and inflate their shape
83+
/// @param objects input objects
84+
/// @param velocity_threshold minimum velocity for an object to be selected
85+
/// @param skip_pedestrians if true, pedestrians are not selected regardless of their velocities
86+
/// @param inflate_size [m] size by which the shape of the selected objects are inflated
87+
/// @return selected and inflated objects
88+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
89+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
90+
const double velocity_threshold, const bool skip_pedestrians, const double inflate_size);
91+
92+
/// @brief clear occlusions behind the given objects
93+
/// @details masks behind the object assuming rays from the center of the grid map
94+
/// @param grid_map grid map
95+
/// @param objects objects
96+
void clear_occlusions_behind_objects(
97+
grid_map::GridMap & grid_map,
98+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects);
99+
82100
/// @brief update timers so that the slowdown activates if the initial time is older than the buffer
83101
/// @param initial_time initial time
84102
/// @param most_recent_slowdown_time time to set only if initial_time is older than the buffer

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -165,7 +165,8 @@ class CrosswalkModule : public SceneModuleInterface
165165
int occlusion_occupied_min;
166166
bool occlusion_ignore_with_traffic_light;
167167
bool occlusion_ignore_behind_predicted_objects;
168-
double occlusion_min_objects_velocity;
168+
bool occlusion_do_not_ignore_behind_pedestrians;
169+
double occlusion_ignore_velocity_threshold;
169170
double occlusion_extra_objects_size;
170171
};
171172

0 commit comments

Comments
 (0)