|
| 1 | +// Copyright 2020 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 | +/* |
| 16 | + * Copyright (c) 2018, Nagoya University |
| 17 | + * All rights reserved. |
| 18 | + * |
| 19 | + * Redistribution and use in source and binary forms, with or without |
| 20 | + * modification, are permitted provided that the following conditions are met: |
| 21 | + * |
| 22 | + * * Redistributions of source code must retain the above copyright notice, this |
| 23 | + * list of conditions and the following disclaimer. |
| 24 | + * |
| 25 | + * * Redistributions in binary form must reproduce the above copyright notice, |
| 26 | + * this list of conditions and the following disclaimer in the documentation |
| 27 | + * and/or other materials provided with the distribution. |
| 28 | + * |
| 29 | + * * Neither the name of Autoware nor the names of its |
| 30 | + * contributors may be used to endorse or promote products derived from |
| 31 | + * this software without specific prior written permission. |
| 32 | + * |
| 33 | + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 34 | + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 35 | + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE |
| 36 | + * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE |
| 37 | + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL |
| 38 | + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR |
| 39 | + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 40 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, |
| 41 | + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
| 42 | + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
| 43 | + ********************/ |
| 44 | + |
| 45 | +#include "costmap_generator/objects_to_costmap.hpp" |
| 46 | + |
| 47 | +#include <tf2/utils.h> |
| 48 | + |
| 49 | +#include <cmath> |
| 50 | +#include <string> |
| 51 | + |
| 52 | +// Constructor |
| 53 | +ObjectsToCostmap::ObjectsToCostmap() |
| 54 | +: NUMBER_OF_POINTS(4), |
| 55 | + NUMBER_OF_DIMENSIONS(2), |
| 56 | + OBJECTS_COSTMAP_LAYER_("objects_costmap"), |
| 57 | + BLURRED_OBJECTS_COSTMAP_LAYER_("blurred_objects_costmap") |
| 58 | +{ |
| 59 | +} |
| 60 | + |
| 61 | +Eigen::MatrixXd ObjectsToCostmap::makeRectanglePoints( |
| 62 | + const autoware_auto_perception_msgs::msg::PredictedObject & in_object, |
| 63 | + const double expand_rectangle_size) |
| 64 | +{ |
| 65 | + double length = in_object.shape.dimensions.x + expand_rectangle_size; |
| 66 | + double width = in_object.shape.dimensions.y + expand_rectangle_size; |
| 67 | + Eigen::MatrixXd origin_points(NUMBER_OF_DIMENSIONS, NUMBER_OF_POINTS); |
| 68 | + origin_points << length / 2, length / 2, -length / 2, -length / 2, width / 2, -width / 2, |
| 69 | + -width / 2, width / 2; |
| 70 | + |
| 71 | + double yaw = tf2::getYaw(in_object.kinematics.initial_pose_with_covariance.pose.orientation); |
| 72 | + Eigen::MatrixXd rotation_matrix(NUMBER_OF_DIMENSIONS, NUMBER_OF_DIMENSIONS); |
| 73 | + rotation_matrix << std::cos(yaw), -std::sin(yaw), std::sin(yaw), std::cos(yaw); |
| 74 | + Eigen::MatrixXd rotated_points = rotation_matrix * origin_points; |
| 75 | + |
| 76 | + double dx = in_object.kinematics.initial_pose_with_covariance.pose.position.x; |
| 77 | + double dy = in_object.kinematics.initial_pose_with_covariance.pose.position.y; |
| 78 | + Eigen::MatrixXd transformed_points(NUMBER_OF_DIMENSIONS, NUMBER_OF_POINTS); |
| 79 | + Eigen::MatrixXd ones = Eigen::MatrixXd::Ones(1, NUMBER_OF_POINTS); |
| 80 | + transformed_points.row(0) = rotated_points.row(0) + dx * ones; |
| 81 | + transformed_points.row(1) = rotated_points.row(1) + dy * ones; |
| 82 | + |
| 83 | + return transformed_points; |
| 84 | +} |
| 85 | + |
| 86 | +grid_map::Polygon ObjectsToCostmap::makePolygonFromObjectBox( |
| 87 | + const std_msgs::msg::Header & header, |
| 88 | + const autoware_auto_perception_msgs::msg::PredictedObject & in_object, |
| 89 | + const double expand_rectangle_size) |
| 90 | +{ |
| 91 | + grid_map::Polygon polygon; |
| 92 | + polygon.setFrameId(header.frame_id); |
| 93 | + |
| 94 | + Eigen::MatrixXd rectangle_points = makeRectanglePoints(in_object, expand_rectangle_size); |
| 95 | + for (int col = 0; col < rectangle_points.cols(); col++) { |
| 96 | + polygon.addVertex(grid_map::Position(rectangle_points(0, col), rectangle_points(1, col))); |
| 97 | + } |
| 98 | + |
| 99 | + return polygon; |
| 100 | +} |
| 101 | + |
| 102 | +geometry_msgs::msg::Point ObjectsToCostmap::makeExpandedPoint( |
| 103 | + const geometry_msgs::msg::Point & in_centroid, |
| 104 | + const geometry_msgs::msg::Point32 & in_corner_point, const double expand_polygon_size) |
| 105 | +{ |
| 106 | + geometry_msgs::msg::Point expanded_point; |
| 107 | + |
| 108 | + if (expand_polygon_size == 0) { |
| 109 | + expanded_point.x = in_corner_point.x; |
| 110 | + expanded_point.y = in_corner_point.y; |
| 111 | + return expanded_point; |
| 112 | + } |
| 113 | + |
| 114 | + double theta = std::atan2(in_corner_point.y - in_centroid.y, in_corner_point.x - in_centroid.x); |
| 115 | + double delta_x = expand_polygon_size * std::cos(theta); |
| 116 | + double delta_y = expand_polygon_size * std::sin(theta); |
| 117 | + expanded_point.x = in_centroid.x + in_corner_point.x + delta_x; |
| 118 | + expanded_point.y = in_centroid.y + in_corner_point.y + delta_y; |
| 119 | + |
| 120 | + return expanded_point; |
| 121 | +} |
| 122 | + |
| 123 | +grid_map::Polygon ObjectsToCostmap::makePolygonFromObjectConvexHull( |
| 124 | + const std_msgs::msg::Header & header, |
| 125 | + const autoware_auto_perception_msgs::msg::PredictedObject & in_object, |
| 126 | + const double expand_polygon_size) |
| 127 | +{ |
| 128 | + grid_map::Polygon polygon; |
| 129 | + polygon.setFrameId(header.frame_id); |
| 130 | + |
| 131 | + double initial_z = in_object.shape.footprint.points[0].z; |
| 132 | + for (size_t index = 0; index < in_object.shape.footprint.points.size(); index++) { |
| 133 | + if (in_object.shape.footprint.points[index].z == initial_z) { |
| 134 | + geometry_msgs::msg::Point centroid = |
| 135 | + in_object.kinematics.initial_pose_with_covariance.pose.position; |
| 136 | + geometry_msgs::msg::Point expanded_point = |
| 137 | + makeExpandedPoint(centroid, in_object.shape.footprint.points[index], expand_polygon_size); |
| 138 | + polygon.addVertex(grid_map::Position(expanded_point.x, expanded_point.y)); |
| 139 | + } |
| 140 | + } |
| 141 | + |
| 142 | + return polygon; |
| 143 | +} |
| 144 | + |
| 145 | +void ObjectsToCostmap::setCostInPolygon( |
| 146 | + const grid_map::Polygon & polygon, const std::string & gridmap_layer_name, const float score, |
| 147 | + grid_map::GridMap & objects_costmap) |
| 148 | +{ |
| 149 | + for (grid_map::PolygonIterator itr(objects_costmap, polygon); !itr.isPastEnd(); ++itr) { |
| 150 | + const float current_score = objects_costmap.at(gridmap_layer_name, *itr); |
| 151 | + if (score > current_score) { |
| 152 | + objects_costmap.at(gridmap_layer_name, *itr) = score; |
| 153 | + } |
| 154 | + } |
| 155 | +} |
| 156 | + |
| 157 | +grid_map::Matrix ObjectsToCostmap::makeCostmapFromObjects( |
| 158 | + const grid_map::GridMap & costmap, const double expand_polygon_size, |
| 159 | + const double size_of_expansion_kernel, |
| 160 | + const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr in_objects) |
| 161 | +{ |
| 162 | + grid_map::GridMap objects_costmap = costmap; |
| 163 | + objects_costmap.add(OBJECTS_COSTMAP_LAYER_, 0); |
| 164 | + objects_costmap.add(BLURRED_OBJECTS_COSTMAP_LAYER_, 0); |
| 165 | + |
| 166 | + for (const auto & object : in_objects->objects) { |
| 167 | + grid_map::Polygon polygon; |
| 168 | + if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON) { |
| 169 | + polygon = makePolygonFromObjectConvexHull(in_objects->header, object, expand_polygon_size); |
| 170 | + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) { |
| 171 | + polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size); |
| 172 | + } else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) { |
| 173 | + // TODO(Kenji Miyake): Add makePolygonFromObjectCylinder |
| 174 | + polygon = makePolygonFromObjectBox(in_objects->header, object, expand_polygon_size); |
| 175 | + } |
| 176 | + const auto highest_probability_label = *std::max_element( |
| 177 | + object.classification.begin(), object.classification.end(), |
| 178 | + [](const auto & c1, const auto & c2) { return c1.probability < c2.probability; }); |
| 179 | + const double highest_probability = static_cast<double>(highest_probability_label.probability); |
| 180 | + setCostInPolygon(polygon, OBJECTS_COSTMAP_LAYER_, highest_probability, objects_costmap); |
| 181 | + setCostInPolygon(polygon, BLURRED_OBJECTS_COSTMAP_LAYER_, highest_probability, objects_costmap); |
| 182 | + } |
| 183 | + |
| 184 | + // Applying mean filter to expanded gridmap |
| 185 | + const grid_map::SlidingWindowIterator::EdgeHandling edge_handling = |
| 186 | + grid_map::SlidingWindowIterator::EdgeHandling::CROP; |
| 187 | + for (grid_map::SlidingWindowIterator iterator( |
| 188 | + objects_costmap, BLURRED_OBJECTS_COSTMAP_LAYER_, edge_handling, size_of_expansion_kernel); |
| 189 | + !iterator.isPastEnd(); ++iterator) { |
| 190 | + objects_costmap.at(BLURRED_OBJECTS_COSTMAP_LAYER_, *iterator) = |
| 191 | + iterator.getData().meanOfFinites(); // Blurring. |
| 192 | + } |
| 193 | + |
| 194 | + objects_costmap[OBJECTS_COSTMAP_LAYER_] = objects_costmap[OBJECTS_COSTMAP_LAYER_].cwiseMax( |
| 195 | + objects_costmap[BLURRED_OBJECTS_COSTMAP_LAYER_]); |
| 196 | + |
| 197 | + return objects_costmap[OBJECTS_COSTMAP_LAYER_]; |
| 198 | +} |
0 commit comments