|
| 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 |
0 commit comments