@@ -94,10 +94,30 @@ std::vector<lanelet::BasicPolygon2d> calculate_detection_areas(
94
94
return detection_areas;
95
95
}
96
96
97
- void clear_behind_objects (
98
- grid_map::GridMap & grid_map,
97
+ std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects (
99
98
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)
101
121
{
102
122
const auto angle_cmp = [&](const auto & p1, const auto & p2) {
103
123
const auto d1 = p1 - grid_map.getPosition ();
@@ -107,14 +127,10 @@ void clear_behind_objects(
107
127
const lanelet::BasicPoint2d grid_map_position = grid_map.getPosition ();
108
128
const auto range = grid_map.getLength ().maxCoeff () / 2.0 ;
109
129
for (auto object : objects) {
110
- object.shape .dimensions .x += extra_object_size;
111
- object.shape .dimensions .y += extra_object_size;
112
130
const lanelet::BasicPoint2d object_position = {
113
131
object.kinematics .initial_pose_with_covariance .pose .position .x ,
114
132
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) {
118
134
lanelet::BasicPoints2d edge_points;
119
135
const auto object_polygon = tier4_autoware_utils::toPolygon2d (object);
120
136
for (const auto & edge_point : object_polygon.outer ()) edge_points.push_back (edge_point);
@@ -143,10 +159,12 @@ bool is_crosswalk_occluded(
143
159
grid_map::GridMap grid_map;
144
160
grid_map::GridMapRosConverter::fromOccupancyGrid (occupancy_grid, " layer" , grid_map);
145
161
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
+ }
150
168
const auto min_nb_of_cells = std::ceil (params.occlusion_min_size / grid_map.getResolution ());
151
169
for (const auto & detection_area : calculate_detection_areas (
152
170
crosswalk_lanelet, {path_intersection.x , path_intersection.y }, detection_range)) {
0 commit comments