|
| 1 | +// Copyright 2021 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 FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ |
| 16 | +#define FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ |
| 17 | + |
| 18 | +#include <geometry_msgs/msg/pose_array.hpp> |
| 19 | +#include <nav_msgs/msg/occupancy_grid.hpp> |
| 20 | + |
| 21 | +#include <tf2/utils.h> |
| 22 | +#include <tf2_geometry_msgs/tf2_geometry_msgs.h> |
| 23 | + |
| 24 | +#include <vector> |
| 25 | + |
| 26 | +// TODO(wep21): Remove these apis |
| 27 | +// after they are implemented in ros2 geometry2. |
| 28 | +namespace tf2 |
| 29 | +{ |
| 30 | +inline void fromMsg(const geometry_msgs::msg::Point & in, tf2::Vector3 & out) |
| 31 | +{ |
| 32 | + out = tf2::Vector3(in.x, in.y, in.z); |
| 33 | +} |
| 34 | + |
| 35 | +template <> |
| 36 | +inline void doTransform( |
| 37 | + const geometry_msgs::msg::Pose & t_in, geometry_msgs::msg::Pose & t_out, |
| 38 | + const geometry_msgs::msg::TransformStamped & transform) |
| 39 | +{ |
| 40 | + tf2::Vector3 v; |
| 41 | + fromMsg(t_in.position, v); |
| 42 | + tf2::Quaternion r; |
| 43 | + fromMsg(t_in.orientation, r); |
| 44 | + |
| 45 | + tf2::Transform t; |
| 46 | + fromMsg(transform.transform, t); |
| 47 | + tf2::Transform v_out = t * tf2::Transform(r, v); |
| 48 | + toMsg(v_out, t_out); |
| 49 | +} |
| 50 | +} // namespace tf2 |
| 51 | + |
| 52 | +namespace freespace_planning_algorithms |
| 53 | +{ |
| 54 | +int discretizeAngle(const double theta, const int theta_size); |
| 55 | + |
| 56 | +struct IndexXYT |
| 57 | +{ |
| 58 | + int x; |
| 59 | + int y; |
| 60 | + int theta; |
| 61 | +}; |
| 62 | + |
| 63 | +struct IndexXY |
| 64 | +{ |
| 65 | + int x; |
| 66 | + int y; |
| 67 | +}; |
| 68 | + |
| 69 | +IndexXYT pose2index( |
| 70 | + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local, |
| 71 | + const int theta_size); |
| 72 | + |
| 73 | +geometry_msgs::msg::Pose index2pose( |
| 74 | + const nav_msgs::msg::OccupancyGrid & costmap, const IndexXYT & index, const int theta_size); |
| 75 | + |
| 76 | +geometry_msgs::msg::Pose global2local( |
| 77 | + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_global); |
| 78 | + |
| 79 | +geometry_msgs::msg::Pose local2global( |
| 80 | + const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local); |
| 81 | + |
| 82 | +struct VehicleShape |
| 83 | +{ |
| 84 | + double length; // X [m] |
| 85 | + double width; // Y [m] |
| 86 | + double base2back; // base_link to rear [m] |
| 87 | +}; |
| 88 | + |
| 89 | +struct PlannerCommonParam |
| 90 | +{ |
| 91 | + // base configs |
| 92 | + double time_limit; // planning time limit [msec] |
| 93 | + |
| 94 | + // robot configs |
| 95 | + VehicleShape vehicle_shape; |
| 96 | + double minimum_turning_radius; // [m] |
| 97 | + double maximum_turning_radius; // [m] |
| 98 | + int turning_radius_size; // discretized turning radius table size [-] |
| 99 | + |
| 100 | + // search configs |
| 101 | + int theta_size; // discretized angle table size [-] |
| 102 | + double curve_weight; // curve moving cost [-] |
| 103 | + double reverse_weight; // backward moving cost [-] |
| 104 | + double lateral_goal_range; // reaching threshold, lateral error [m] |
| 105 | + double longitudinal_goal_range; // reaching threshold, longitudinal error [m] |
| 106 | + double angle_goal_range; // reaching threshold, angle error [deg] |
| 107 | + |
| 108 | + // costmap configs |
| 109 | + int obstacle_threshold; // obstacle threshold on grid [-] |
| 110 | +}; |
| 111 | + |
| 112 | +struct PlannerWaypoint |
| 113 | +{ |
| 114 | + geometry_msgs::msg::PoseStamped pose; |
| 115 | + bool is_back = false; |
| 116 | +}; |
| 117 | + |
| 118 | +struct PlannerWaypoints |
| 119 | +{ |
| 120 | + std_msgs::msg::Header header; |
| 121 | + std::vector<PlannerWaypoint> waypoints; |
| 122 | +}; |
| 123 | + |
| 124 | +class AbstractPlanningAlgorithm |
| 125 | +{ |
| 126 | +public: |
| 127 | + explicit AbstractPlanningAlgorithm(const PlannerCommonParam & planner_common_param) |
| 128 | + : planner_common_param_(planner_common_param) |
| 129 | + { |
| 130 | + } |
| 131 | + virtual void setMap(const nav_msgs::msg::OccupancyGrid & costmap); |
| 132 | + virtual bool makePlan( |
| 133 | + const geometry_msgs::msg::Pose & start_pose, const geometry_msgs::msg::Pose & goal_pose) = 0; |
| 134 | + virtual bool hasFeasibleSolution() = 0; // currently used only in testing |
| 135 | + void setVehicleShape(const VehicleShape & vehicle_shape) |
| 136 | + { |
| 137 | + planner_common_param_.vehicle_shape = vehicle_shape; |
| 138 | + } |
| 139 | + bool hasObstacleOnTrajectory(const geometry_msgs::msg::PoseArray & trajectory); |
| 140 | + const PlannerWaypoints & getWaypoints() const { return waypoints_; } |
| 141 | + virtual ~AbstractPlanningAlgorithm() {} |
| 142 | + |
| 143 | +protected: |
| 144 | + void computeCollisionIndexes(int theta_index, std::vector<IndexXY> & indexes); |
| 145 | + bool detectCollision(const IndexXYT & base_index); |
| 146 | + inline bool isOutOfRange(const IndexXYT & index) |
| 147 | + { |
| 148 | + if (index.x < 0 || static_cast<int>(costmap_.info.width) <= index.x) { |
| 149 | + return true; |
| 150 | + } |
| 151 | + if (index.y < 0 || static_cast<int>(costmap_.info.height) <= index.y) { |
| 152 | + return true; |
| 153 | + } |
| 154 | + return false; |
| 155 | + } |
| 156 | + inline bool isObs(const IndexXYT & index) |
| 157 | + { |
| 158 | + // NOTE: Accessing by .at() instead makes 1.2 times slower here. |
| 159 | + // Also, boundary check is already done in isOutOfRange before calling this function. |
| 160 | + // So, basically .at() is not necessary. |
| 161 | + return is_obstacle_table_[index.y][index.x]; |
| 162 | + } |
| 163 | + |
| 164 | + PlannerCommonParam planner_common_param_; |
| 165 | + |
| 166 | + // costmap as occupancy grid |
| 167 | + nav_msgs::msg::OccupancyGrid costmap_; |
| 168 | + |
| 169 | + // collision indexes cache |
| 170 | + std::vector<std::vector<IndexXY>> coll_indexes_table_; |
| 171 | + |
| 172 | + // is_obstacle's table |
| 173 | + std::vector<std::vector<bool>> is_obstacle_table_; |
| 174 | + |
| 175 | + // pose in costmap frame |
| 176 | + geometry_msgs::msg::Pose start_pose_; |
| 177 | + geometry_msgs::msg::Pose goal_pose_; |
| 178 | + |
| 179 | + // result path |
| 180 | + PlannerWaypoints waypoints_; |
| 181 | +}; |
| 182 | + |
| 183 | +} // namespace freespace_planning_algorithms |
| 184 | + |
| 185 | +#endif // FREESPACE_PLANNING_ALGORITHMS__ABSTRACT_ALGORITHM_HPP_ |
0 commit comments