25
25
26
26
namespace autoware ::behavior_path_planner
27
27
{
28
- int discretizeAngle (const double theta, const int theta_size);
28
+ /* *
29
+ * @brief Discretizes a given angle into an index within a specified range.
30
+ * @param theta The angle in radians to discretize.
31
+ * @param theta_size The number of discrete bins or angular intervals.
32
+ * @return The discretized angle as an integer index.
33
+ */
34
+ int discretize_angle (const double theta, const int theta_size);
29
35
30
36
struct IndexXYT
31
37
{
@@ -40,19 +46,36 @@ struct IndexXY
40
46
int y;
41
47
};
42
48
49
+ /* *
50
+ * @brief Converts a given local pose into a 3D grid index (x, y, theta).
51
+ * @param costmap The occupancy grid used for indexing.
52
+ * @param pose_local The local pose.
53
+ * @param theta_size The number of discrete angular intervals for yaw.
54
+ * @return IndexXYT The grid index representing the position and discretized orientation.
55
+ */
43
56
IndexXYT pose2index (
44
57
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local,
45
58
const int theta_size);
46
59
60
+ /* *
61
+ * @brief Converts a grid index (x, y, theta) back into a pose in the local frame.
62
+ * @param costmap The occupancy grid used for indexing.
63
+ * @param index The grid index containing x, y, and theta.
64
+ * @param theta_size The number of discrete angular intervals for yaw.
65
+ * @return geometry_msgs::msg::Pose The corresponding local pose.
66
+ */
47
67
geometry_msgs::msg::Pose index2pose (
48
68
const nav_msgs::msg::OccupancyGrid & costmap, const IndexXYT & index, const int theta_size);
49
69
70
+ /* *
71
+ * @brief Transforms a global pose into a local pose relative to the costmap's origin.
72
+ * @param costmap The occupancy grid that defines the local frame.
73
+ * @param pose_global The global pose to transform.
74
+ * @return geometry_msgs::msg::Pose The transformed pose in the local frame.
75
+ */
50
76
geometry_msgs::msg::Pose global2local (
51
77
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_global);
52
78
53
- geometry_msgs::msg::Pose local2global (
54
- const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local);
55
-
56
79
struct VehicleShape
57
80
{
58
81
double length; // X [m]
@@ -76,12 +99,6 @@ struct PlannerWaypoint
76
99
bool is_back = false ;
77
100
};
78
101
79
- struct PlannerWaypoints
80
- {
81
- std_msgs::msg::Header header;
82
- std::vector<PlannerWaypoint> waypoints;
83
- };
84
-
85
102
class OccupancyGridBasedCollisionDetector
86
103
{
87
104
public:
@@ -92,21 +109,40 @@ class OccupancyGridBasedCollisionDetector
92
109
default ;
93
110
OccupancyGridBasedCollisionDetector & operator =(OccupancyGridBasedCollisionDetector &&) = delete ;
94
111
void setParam (const OccupancyGridMapParam & param) { param_ = param; };
95
- OccupancyGridMapParam getParam () const { return param_; };
112
+ [[nodiscard]] OccupancyGridMapParam getParam () const { return param_; };
96
113
void setMap (const nav_msgs::msg::OccupancyGrid & costmap);
97
- nav_msgs::msg::OccupancyGrid getMap () const { return costmap_; };
98
- void setVehicleShape (const VehicleShape & vehicle_shape) { param_.vehicle_shape = vehicle_shape; }
99
- bool hasObstacleOnPath (
100
- const geometry_msgs::msg::PoseArray & path, const bool check_out_of_range) const ;
101
- bool hasObstacleOnPath (
114
+ [[nodiscard]] nav_msgs::msg::OccupancyGrid getMap () const { return costmap_; };
115
+
116
+ /* *
117
+ * @brief Detects if a collision occurs with given path.
118
+ * @param path The path to check collision defined in a global frame
119
+ * @param check_out_of_range A boolean flag indicating whether out-of-range conditions is
120
+ * collision
121
+ * @return true if a collision is detected, false if no collision is detected.
122
+ */
123
+ [[nodiscard]] bool hasObstacleOnPath (
102
124
const tier4_planning_msgs::msg::PathWithLaneId & path, const bool check_out_of_range) const ;
103
- const PlannerWaypoints & getWaypoints () const { return waypoints_; }
104
- bool detectCollision (const IndexXYT & base_index, const bool check_out_of_range) const ;
125
+
126
+ /* *
127
+ * @brief Detects if a collision occurs at the specified base index in the occupancy grid map.
128
+ * @param base_index The 3D index (x, y, theta) of the base position in the occupancy grid.
129
+ * @param check_out_of_range A boolean flag indicating whether out-of-range conditions is
130
+ * collision
131
+ * @return true if a collision is detected, false if no collision is detected.
132
+ */
133
+ [[nodiscard]] bool detectCollision (
134
+ const IndexXYT & base_index, const bool check_out_of_range) const ;
105
135
virtual ~OccupancyGridBasedCollisionDetector () = default ;
106
136
107
137
protected:
108
- void computeCollisionIndexes (int theta_index, std::vector<IndexXY> & indexes);
109
- inline bool isOutOfRange (const IndexXYT & index) const
138
+ /* *
139
+ * @brief Computes the 2D grid indexes where collision might occur for a given theta index.
140
+ * @param theta_index The discretized orientation index for yaw.
141
+ * @param indexes_2d The output vector of 2D grid indexes where collisions could happen.
142
+ */
143
+ void compute_collision_indexes (int theta_index, std::vector<IndexXY> & indexes);
144
+
145
+ [[nodiscard]] inline bool is_out_of_range (const IndexXYT & index) const
110
146
{
111
147
if (index .x < 0 || static_cast <int >(costmap_.info .width ) <= index .x ) {
112
148
return true ;
@@ -116,7 +152,7 @@ class OccupancyGridBasedCollisionDetector
116
152
}
117
153
return false ;
118
154
}
119
- inline bool isObs (const IndexXYT & index) const
155
+ [[nodiscard]] inline bool is_obs (const IndexXYT & index) const
120
156
{
121
157
// NOTE: Accessing by .at() instead makes 1.2 times slower here.
122
158
// Also, boundary check is already done in isOutOfRange before calling this function.
@@ -134,15 +170,7 @@ class OccupancyGridBasedCollisionDetector
134
170
135
171
// is_obstacle's table
136
172
std::vector<std::vector<bool >> is_obstacle_table_;
137
-
138
- // pose in costmap frame
139
- geometry_msgs::msg::Pose start_pose_;
140
- geometry_msgs::msg::Pose goal_pose_;
141
-
142
- // result path
143
- PlannerWaypoints waypoints_;
144
173
};
145
-
146
174
} // namespace autoware::behavior_path_planner
147
175
148
176
#endif // AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_
0 commit comments