|
| 1 | +// Copyright 2020 Tier IV, Inc. All rights reserved. |
| 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 OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_ |
| 16 | +#define OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_ |
| 17 | + |
| 18 | +#include <autoware_utils/geometry/boost_geometry.hpp> |
| 19 | +#include <vehicle_info_util/vehicle_info_util.hpp> |
| 20 | + |
| 21 | +#include <autoware_auto_planning_msgs/msg/trajectory.hpp> |
| 22 | +#include <geometry_msgs/msg/pose_stamped.hpp> |
| 23 | +#include <geometry_msgs/msg/transform_stamped.hpp> |
| 24 | +#include <geometry_msgs/msg/twist.hpp> |
| 25 | +#include <sensor_msgs/msg/point_cloud2.hpp> |
| 26 | + |
| 27 | +#include <boost/optional.hpp> |
| 28 | + |
| 29 | +#include <pcl/point_cloud.h> |
| 30 | +#include <pcl/point_types.h> |
| 31 | + |
| 32 | +#include <map> |
| 33 | +#include <string> |
| 34 | +#include <vector> |
| 35 | + |
| 36 | +namespace obstacle_collision_checker |
| 37 | +{ |
| 38 | +using autoware_utils::LinearRing2d; |
| 39 | + |
| 40 | +struct Param |
| 41 | +{ |
| 42 | + double delay_time; |
| 43 | + double footprint_margin; |
| 44 | + double max_deceleration; |
| 45 | + double resample_interval; |
| 46 | + double search_radius; |
| 47 | +}; |
| 48 | + |
| 49 | +struct Input |
| 50 | +{ |
| 51 | + geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose; |
| 52 | + geometry_msgs::msg::Twist::ConstSharedPtr current_twist; |
| 53 | + sensor_msgs::msg::PointCloud2::ConstSharedPtr obstacle_pointcloud; |
| 54 | + geometry_msgs::msg::TransformStamped::ConstSharedPtr obstacle_transform; |
| 55 | + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory; |
| 56 | + autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory; |
| 57 | +}; |
| 58 | + |
| 59 | +struct Output |
| 60 | +{ |
| 61 | + std::map<std::string, double> processing_time_map; |
| 62 | + bool will_collide; |
| 63 | + autoware_auto_planning_msgs::msg::Trajectory resampled_trajectory; |
| 64 | + std::vector<LinearRing2d> vehicle_footprints; |
| 65 | + std::vector<LinearRing2d> vehicle_passing_areas; |
| 66 | +}; |
| 67 | + |
| 68 | +class ObstacleCollisionChecker |
| 69 | +{ |
| 70 | +public: |
| 71 | + explicit ObstacleCollisionChecker(rclcpp::Node & node); |
| 72 | + Output update(const Input & input); |
| 73 | + |
| 74 | + void setParam(const Param & param) { param_ = param; } |
| 75 | + |
| 76 | +private: |
| 77 | + Param param_; |
| 78 | + vehicle_info_util::VehicleInfo vehicle_info_; |
| 79 | + |
| 80 | + //! This function assumes the input trajectory is sampled dense enough |
| 81 | + static autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory( |
| 82 | + const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const double interval); |
| 83 | + |
| 84 | + static autoware_auto_planning_msgs::msg::Trajectory cutTrajectory( |
| 85 | + const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const double length); |
| 86 | + |
| 87 | + static std::vector<LinearRing2d> createVehicleFootprints( |
| 88 | + const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const Param & param, |
| 89 | + const vehicle_info_util::VehicleInfo & vehicle_info); |
| 90 | + |
| 91 | + static std::vector<LinearRing2d> createVehiclePassingAreas( |
| 92 | + const std::vector<LinearRing2d> & vehicle_footprints); |
| 93 | + |
| 94 | + static LinearRing2d createHullFromFootprints( |
| 95 | + const LinearRing2d & area1, const LinearRing2d & area2); |
| 96 | + |
| 97 | + static bool willCollide( |
| 98 | + const pcl::PointCloud<pcl::PointXYZ> & obstacle_pointcloud, |
| 99 | + const std::vector<LinearRing2d> & vehicle_footprints); |
| 100 | + |
| 101 | + static bool hasCollision( |
| 102 | + const pcl::PointCloud<pcl::PointXYZ> & obstacle_pointcloud, |
| 103 | + const LinearRing2d & vehicle_footprint); |
| 104 | +}; |
| 105 | +} // namespace obstacle_collision_checker |
| 106 | + |
| 107 | +#endif // OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_ |
0 commit comments