Skip to content

Commit beeaba3

Browse files
authored
Merge pull request #1147 from maxime-clem/beta/v0.20.1+PR6122
feat(crosswalk): add option to slowdown at occluded crosswalks (autowarefoundation#6122)
2 parents 60b0286 + 49bd861 commit beeaba3

File tree

8 files changed

+399
-14
lines changed

8 files changed

+399
-14
lines changed

planning/behavior_velocity_crosswalk_module/CMakeLists.txt

+2-4
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,8 @@ autoware_package()
66
pluginlib_export_plugin_description_file(behavior_velocity_planner plugins.xml)
77

88
ament_auto_add_library(${PROJECT_NAME} SHARED
9-
src/debug.cpp
10-
src/manager.cpp
11-
src/scene_crosswalk.cpp
12-
src/util.cpp
9+
DIRECTORY
10+
src
1311
)
1412

1513
ament_auto_package(INSTALL_TO_SHARE config)

planning/behavior_velocity_crosswalk_module/config/crosswalk.param.yaml

+17
Original file line numberDiff line numberDiff line change
@@ -68,3 +68,20 @@
6868
bicycle: true # [-] whether to look and stop by BICYCLE objects
6969
motorcycle: true # [-] whether to look and stop by MOTORCYCLE objects (tmp: currently it is difficult for perception modules to detect bicycles and motorcycles separately.)
7070
pedestrian: true # [-] whether to look and stop by PEDESTRIAN objects
71+
72+
# param for occlusions
73+
occlusion:
74+
enable: true # if true, ego will slowdown around crosswalks that are occluded
75+
occluded_object_velocity: 1.0 # [m/s] assumed velocity of objects that may come out of the occluded space
76+
slow_down_velocity: 1.0 # [m/s]
77+
time_buffer: 1.0 # [s] consecutive time with/without an occlusion to add/remove the slowdown
78+
min_size: 0.5 # [m] minimum size of an occlusion (square side size)
79+
free_space_max: 43 # [-] maximum value of a free space cell in the occupancy grid
80+
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
82+
ignore_behind_predicted_objects: true # [-] if true, occlusions behind predicted objects are ignored
83+
ignore_velocity_thresholds:
84+
default: 0.5 # [m/s] occlusions are only ignored behind objects with a higher or equal velocity
85+
custom_labels: ["PEDESTRIAN"] # labels for which to define a non-default velocity threshold (see autoware_auto_perception_msgs::msg::ObjectClassification for all the labels)
86+
custom_thresholds: [0.0] # velocities of the custom labels
87+
extra_predicted_objects_size: 0.5 # [m] extra size added to the objects for masking the occlusions

planning/behavior_velocity_crosswalk_module/package.xml

+5
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,14 @@
2828
<depend>behavior_velocity_planner_common</depend>
2929
<depend>eigen</depend>
3030
<depend>geometry_msgs</depend>
31+
<depend>grid_map_core</depend>
32+
<depend>grid_map_ros</depend>
33+
<depend>grid_map_utils</depend>
34+
<depend>interpolation</depend>
3135
<depend>lanelet2_extension</depend>
3236
<depend>libboost-dev</depend>
3337
<depend>motion_utils</depend>
38+
<depend>nav_msgs</depend>
3439
<depend>pcl_conversions</depend>
3540
<depend>pluginlib</depend>
3641
<depend>rclcpp</depend>

planning/behavior_velocity_crosswalk_module/src/manager.cpp

+41
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
#include <behavior_velocity_planner_common/utilization/util.hpp>
1818
#include <tier4_autoware_utils/ros/parameter.hpp>
1919

20+
#include <algorithm>
2021
#include <limits>
2122
#include <memory>
2223
#include <set>
@@ -123,6 +124,46 @@ CrosswalkModuleManager::CrosswalkModuleManager(rclcpp::Node & node)
123124
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.motorcycle");
124125
cp.look_pedestrian =
125126
getOrDeclareParameter<bool>(node, ns + ".object_filtering.target_object.pedestrian");
127+
128+
// param for occlusions
129+
cp.occlusion_enable = getOrDeclareParameter<bool>(node, ns + ".occlusion.enable");
130+
cp.occlusion_occluded_object_velocity =
131+
getOrDeclareParameter<double>(node, ns + ".occlusion.occluded_object_velocity");
132+
cp.occlusion_slow_down_velocity =
133+
getOrDeclareParameter<float>(node, ns + ".occlusion.slow_down_velocity");
134+
cp.occlusion_time_buffer = getOrDeclareParameter<double>(node, ns + ".occlusion.time_buffer");
135+
cp.occlusion_min_size = getOrDeclareParameter<double>(node, ns + ".occlusion.min_size");
136+
cp.occlusion_free_space_max = getOrDeclareParameter<int>(node, ns + ".occlusion.free_space_max");
137+
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");
140+
cp.occlusion_ignore_behind_predicted_objects =
141+
getOrDeclareParameter<bool>(node, ns + ".occlusion.ignore_behind_predicted_objects");
142+
143+
cp.occlusion_ignore_velocity_thresholds.resize(
144+
autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN + 1,
145+
getOrDeclareParameter<double>(node, ns + ".occlusion.ignore_velocity_thresholds.default"));
146+
const auto get_label = [](const std::string & s) {
147+
if (s == "CAR") return autoware_auto_perception_msgs::msg::ObjectClassification::CAR;
148+
if (s == "TRUCK") return autoware_auto_perception_msgs::msg::ObjectClassification::TRUCK;
149+
if (s == "BUS") return autoware_auto_perception_msgs::msg::ObjectClassification::BUS;
150+
if (s == "TRAILER") return autoware_auto_perception_msgs::msg::ObjectClassification::TRAILER;
151+
if (s == "MOTORCYCLE")
152+
return autoware_auto_perception_msgs::msg::ObjectClassification::MOTORCYCLE;
153+
if (s == "BICYCLE") return autoware_auto_perception_msgs::msg::ObjectClassification::BICYCLE;
154+
if (s == "PEDESTRIAN")
155+
return autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
156+
return autoware_auto_perception_msgs::msg::ObjectClassification::UNKNOWN;
157+
};
158+
const auto custom_labels = getOrDeclareParameter<std::vector<std::string>>(
159+
node, ns + ".occlusion.ignore_velocity_thresholds.custom_labels");
160+
const auto custom_velocities = getOrDeclareParameter<std::vector<double>>(
161+
node, ns + ".occlusion.ignore_velocity_thresholds.custom_thresholds");
162+
for (auto idx = 0UL; idx < std::min(custom_labels.size(), custom_velocities.size()); ++idx) {
163+
cp.occlusion_ignore_velocity_thresholds[get_label(custom_labels[idx])] = custom_velocities[idx];
164+
}
165+
cp.occlusion_extra_objects_size =
166+
getOrDeclareParameter<double>(node, ns + ".occlusion.extra_predicted_objects_size");
126167
}
127168

128169
void CrosswalkModuleManager::launchNewModules(const PathWithLaneId & path)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,173 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "occluded_crosswalk.hpp"
16+
17+
#include "behavior_velocity_crosswalk_module/util.hpp"
18+
19+
#include <grid_map_ros/GridMapRosConverter.hpp>
20+
#include <grid_map_utils/polygon_iterator.hpp>
21+
22+
#include <algorithm>
23+
#include <vector>
24+
25+
namespace behavior_velocity_planner
26+
{
27+
bool is_occluded(
28+
const grid_map::GridMap & grid_map, const int min_nb_of_cells, const grid_map::Index idx,
29+
const behavior_velocity_planner::CrosswalkModule::PlannerParam & params)
30+
{
31+
grid_map::Index idx_offset;
32+
for (idx_offset.x() = 0; idx_offset.x() < min_nb_of_cells; ++idx_offset.x()) {
33+
for (idx_offset.y() = 0; idx_offset.y() < min_nb_of_cells; ++idx_offset.y()) {
34+
const auto index = idx + idx_offset;
35+
if ((index < grid_map.getSize()).all()) {
36+
const auto cell_value = grid_map.at("layer", index);
37+
if (
38+
cell_value < params.occlusion_free_space_max ||
39+
cell_value > params.occlusion_occupied_min)
40+
return false;
41+
}
42+
}
43+
}
44+
return true;
45+
}
46+
47+
lanelet::BasicPoint2d interpolate_point(
48+
const lanelet::BasicSegment2d & segment, const double extra_distance)
49+
{
50+
const auto direction_vector = (segment.second - segment.first).normalized();
51+
return segment.second + extra_distance * direction_vector;
52+
}
53+
54+
std::vector<lanelet::BasicPolygon2d> calculate_detection_areas(
55+
const lanelet::ConstLanelet & crosswalk_lanelet, const lanelet::BasicPoint2d & crosswalk_origin,
56+
const double detection_range)
57+
{
58+
std::vector<lanelet::BasicPolygon2d> detection_areas = {
59+
crosswalk_lanelet.polygon2d().basicPolygon()};
60+
const std::vector<std::function<lanelet::BasicSegment2d(lanelet::ConstLineString2d)>>
61+
segment_getters = {
62+
[](const auto & ls) -> lanelet::BasicSegment2d {
63+
return {ls[1].basicPoint2d(), ls[0].basicPoint2d()};
64+
},
65+
[](const auto & ls) -> lanelet::BasicSegment2d {
66+
return {ls[ls.size() - 2].basicPoint2d(), ls[ls.size() - 1].basicPoint2d()};
67+
}};
68+
if (
69+
crosswalk_lanelet.centerline2d().size() > 1 && crosswalk_lanelet.leftBound2d().size() > 1 &&
70+
crosswalk_lanelet.rightBound2d().size() > 1) {
71+
for (const auto & segment_getter : segment_getters) {
72+
const auto center_segment = segment_getter(crosswalk_lanelet.centerline2d());
73+
const auto left_segment = segment_getter(crosswalk_lanelet.leftBound2d());
74+
const auto right_segment = segment_getter(crosswalk_lanelet.rightBound2d());
75+
const auto dist = lanelet::geometry::distance2d(center_segment.second, crosswalk_origin);
76+
if (dist < detection_range) {
77+
const auto target_left = interpolate_point(left_segment, detection_range - dist);
78+
const auto target_right = interpolate_point(right_segment, detection_range - dist);
79+
detection_areas.push_back(
80+
{left_segment.second, target_left, target_right, right_segment.second});
81+
}
82+
}
83+
}
84+
return detection_areas;
85+
}
86+
87+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
88+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
89+
const std::vector<double> velocity_thresholds, const double inflate_size)
90+
{
91+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> selected_objects;
92+
for (const auto & o : objects) {
93+
const auto vel_threshold = velocity_thresholds[o.classification.front().label];
94+
if (o.kinematics.initial_twist_with_covariance.twist.linear.x >= vel_threshold) {
95+
auto selected_object = o;
96+
selected_object.shape.dimensions.x += inflate_size;
97+
selected_object.shape.dimensions.y += inflate_size;
98+
selected_objects.push_back(selected_object);
99+
}
100+
}
101+
return selected_objects;
102+
}
103+
104+
void clear_occlusions_behind_objects(
105+
grid_map::GridMap & grid_map,
106+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects)
107+
{
108+
const auto angle_cmp = [&](const auto & p1, const auto & p2) {
109+
const auto d1 = p1 - grid_map.getPosition();
110+
const auto d2 = p2 - grid_map.getPosition();
111+
return std::atan2(d1.y(), d1.x()) < std::atan2(d2.y(), d2.x());
112+
};
113+
const lanelet::BasicPoint2d grid_map_position = grid_map.getPosition();
114+
const auto range = grid_map.getLength().maxCoeff() / 2.0;
115+
for (auto object : objects) {
116+
const lanelet::BasicPoint2d object_position = {
117+
object.kinematics.initial_pose_with_covariance.pose.position.x,
118+
object.kinematics.initial_pose_with_covariance.pose.position.y};
119+
if (lanelet::geometry::distance2d(grid_map_position, object_position) < range) {
120+
lanelet::BasicPoints2d edge_points;
121+
const auto object_polygon = tier4_autoware_utils::toPolygon2d(object);
122+
for (const auto & edge_point : object_polygon.outer()) edge_points.push_back(edge_point);
123+
std::sort(edge_points.begin(), edge_points.end(), angle_cmp);
124+
// points.push_back(interpolate_point({object_position, edge_point}, 10.0 * range));
125+
grid_map::Polygon polygon_to_clear;
126+
polygon_to_clear.addVertex(edge_points.front());
127+
polygon_to_clear.addVertex(
128+
interpolate_point({grid_map_position, edge_points.front()}, 10.0 * range));
129+
polygon_to_clear.addVertex(
130+
interpolate_point({grid_map_position, edge_points.back()}, 10.0 * range));
131+
polygon_to_clear.addVertex(edge_points.back());
132+
for (grid_map_utils::PolygonIterator it(grid_map, polygon_to_clear); !it.isPastEnd(); ++it)
133+
grid_map.at("layer", *it) = 0;
134+
}
135+
}
136+
}
137+
138+
bool is_crosswalk_occluded(
139+
const lanelet::ConstLanelet & crosswalk_lanelet,
140+
const nav_msgs::msg::OccupancyGrid & occupancy_grid,
141+
const geometry_msgs::msg::Point & path_intersection, const double detection_range,
142+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & dynamic_objects,
143+
const behavior_velocity_planner::CrosswalkModule::PlannerParam & params)
144+
{
145+
grid_map::GridMap grid_map;
146+
grid_map::GridMapRosConverter::fromOccupancyGrid(occupancy_grid, "layer", grid_map);
147+
148+
if (params.occlusion_ignore_behind_predicted_objects) {
149+
const auto objects = select_and_inflate_objects(
150+
dynamic_objects, params.occlusion_ignore_velocity_thresholds,
151+
params.occlusion_extra_objects_size);
152+
clear_occlusions_behind_objects(grid_map, objects);
153+
}
154+
const auto min_nb_of_cells = std::ceil(params.occlusion_min_size / grid_map.getResolution());
155+
for (const auto & detection_area : calculate_detection_areas(
156+
crosswalk_lanelet, {path_intersection.x, path_intersection.y}, detection_range)) {
157+
grid_map::Polygon poly;
158+
for (const auto & p : detection_area) poly.addVertex(grid_map::Position(p.x(), p.y()));
159+
for (grid_map_utils::PolygonIterator iter(grid_map, poly); !iter.isPastEnd(); ++iter)
160+
if (is_occluded(grid_map, min_nb_of_cells, *iter, params)) return true;
161+
}
162+
return false;
163+
}
164+
165+
double calculate_detection_range(
166+
const double occluded_object_velocity, const double dist_ego_to_crosswalk,
167+
const double ego_velocity)
168+
{
169+
constexpr double min_ego_velocity = 1.0;
170+
const auto time_to_crosswalk = dist_ego_to_crosswalk / std::max(min_ego_velocity, ego_velocity);
171+
return time_to_crosswalk > 0.0 ? time_to_crosswalk / occluded_object_velocity : 20.0;
172+
}
173+
} // namespace behavior_velocity_planner
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,94 @@
1+
// Copyright 2024 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef OCCLUDED_CROSSWALK_HPP_
16+
#define OCCLUDED_CROSSWALK_HPP_
17+
18+
#include "scene_crosswalk.hpp"
19+
20+
#include <grid_map_core/GridMap.hpp>
21+
#include <rclcpp/time.hpp>
22+
23+
#include <geometry_msgs/msg/point.hpp>
24+
#include <nav_msgs/msg/occupancy_grid.hpp>
25+
26+
#include <lanelet2_core/primitives/Lanelet.h>
27+
#include <lanelet2_core/primitives/Point.h>
28+
29+
#include <optional>
30+
#include <vector>
31+
32+
namespace behavior_velocity_planner
33+
{
34+
/// @brief check if the gridmap is occluded at the given index
35+
/// @param [in] grid_map input grid map
36+
/// @param [in] min_nb_of_cells minimum number of occluded cells needed to detect an occlusion (as
37+
/// side of a square centered at the index)
38+
/// @param [in] idx target index in the grid map
39+
/// @param [in] params parameters
40+
/// @return true if the index is occluded
41+
bool is_occluded(
42+
const grid_map::GridMap & grid_map, const int min_nb_of_cells, const grid_map::Index idx,
43+
const behavior_velocity_planner::CrosswalkModule::PlannerParam & params);
44+
45+
/// @brief interpolate a point beyond the end of the given segment
46+
/// @param [in] segment input segment
47+
/// @param [in] extra_distance desired distance beyond the end of the segment
48+
/// @return interpolated point beyond the end of the segment
49+
lanelet::BasicPoint2d interpolate_point(
50+
const lanelet::BasicSegment2d & segment, const double extra_distance);
51+
52+
/// @brief check if the crosswalk is occluded
53+
/// @param crosswalk_lanelet lanelet of the crosswalk
54+
/// @param occupancy_grid occupancy grid with the occlusion information
55+
/// @param path_intersection intersection between the crosswalk and the ego path
56+
/// @param detection_range range away from the crosswalk until occlusions are considered
57+
/// @param dynamic_objects dynamic objects
58+
/// @param params parameters
59+
/// @return true if the crosswalk is occluded
60+
bool is_crosswalk_occluded(
61+
const lanelet::ConstLanelet & crosswalk_lanelet,
62+
const nav_msgs::msg::OccupancyGrid & occupancy_grid,
63+
const geometry_msgs::msg::Point & path_intersection, const double detection_range,
64+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & dynamic_objects,
65+
const behavior_velocity_planner::CrosswalkModule::PlannerParam & params);
66+
67+
/// @brief calculate the distance away from the crosswalk that should be checked for occlusions
68+
/// @param occluded_objects_velocity assumed velocity of the objects coming out of occlusions
69+
/// @param dist_ego_to_crosswalk distance between ego and the crosswalk
70+
/// @param ego_velocity current velocity of ego
71+
double calculate_detection_range(
72+
const double occluded_object_velocity, const double dist_ego_to_crosswalk,
73+
const double ego_velocity);
74+
75+
/// @brief select a subset of objects meeting the velocity threshold and inflate their shape
76+
/// @param objects input objects
77+
/// @param velocity_threshold minimum velocity for an object to be selected
78+
/// @param skip_pedestrians if true, pedestrians are not selected regardless of their velocities
79+
/// @param inflate_size [m] size by which the shape of the selected objects are inflated
80+
/// @return selected and inflated objects
81+
std::vector<autoware_auto_perception_msgs::msg::PredictedObject> select_and_inflate_objects(
82+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects,
83+
const double velocity_threshold, const bool skip_pedestrians, const double inflate_size);
84+
85+
/// @brief clear occlusions behind the given objects
86+
/// @details masks behind the object assuming rays from the center of the grid map
87+
/// @param grid_map grid map
88+
/// @param objects objects
89+
void clear_occlusions_behind_objects(
90+
grid_map::GridMap & grid_map,
91+
const std::vector<autoware_auto_perception_msgs::msg::PredictedObject> & objects);
92+
} // namespace behavior_velocity_planner
93+
94+
#endif // OCCLUDED_CROSSWALK_HPP_

0 commit comments

Comments
 (0)