Skip to content

Commit b93ddd9

Browse files
authored
test(bpp_common): add test for occupancy grid based collision detector (#9066)
* add test for occupancy grid based collision detector Signed-off-by: Go Sakayori <gsakayori@gmail.com> * remove unnnecessary header Signed-off-by: Go Sakayori <gsakayori@gmail.com> * fix Signed-off-by: Go Sakayori <gsakayori@gmail.com> * change map resolution and corresponding index Signed-off-by: Go Sakayori <gsakayori@gmail.com> --------- Signed-off-by: Go Sakayori <gsakayori@gmail.com>
1 parent 1746798 commit b93ddd9

File tree

4 files changed

+226
-68
lines changed

4 files changed

+226
-68
lines changed

planning/behavior_path_planner/autoware_behavior_path_planner_common/CMakeLists.txt

+8
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,14 @@ if(BUILD_TESTING)
5050
${PROJECT_NAME}
5151
)
5252

53+
ament_add_ros_isolated_gmock(test_${PROJECT_NAME}_occupancy_grid_based_collision_detector
54+
test/test_occupancy_grid_based_collision_detector.cpp
55+
)
56+
57+
target_link_libraries(test_${PROJECT_NAME}_occupancy_grid_based_collision_detector
58+
${PROJECT_NAME}
59+
)
60+
5361
ament_add_ros_isolated_gmock(test_${PROJECT_NAME}_safety_check
5462
test/test_safety_check.cpp
5563
)

planning/behavior_path_planner/autoware_behavior_path_planner_common/include/autoware/behavior_path_planner_common/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.hpp

+57-29
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,13 @@
2525

2626
namespace autoware::behavior_path_planner
2727
{
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);
2935

3036
struct IndexXYT
3137
{
@@ -40,19 +46,36 @@ struct IndexXY
4046
int y;
4147
};
4248

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+
*/
4356
IndexXYT pose2index(
4457
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local,
4558
const int theta_size);
4659

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+
*/
4767
geometry_msgs::msg::Pose index2pose(
4868
const nav_msgs::msg::OccupancyGrid & costmap, const IndexXYT & index, const int theta_size);
4969

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+
*/
5076
geometry_msgs::msg::Pose global2local(
5177
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_global);
5278

53-
geometry_msgs::msg::Pose local2global(
54-
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local);
55-
5679
struct VehicleShape
5780
{
5881
double length; // X [m]
@@ -76,12 +99,6 @@ struct PlannerWaypoint
7699
bool is_back = false;
77100
};
78101

79-
struct PlannerWaypoints
80-
{
81-
std_msgs::msg::Header header;
82-
std::vector<PlannerWaypoint> waypoints;
83-
};
84-
85102
class OccupancyGridBasedCollisionDetector
86103
{
87104
public:
@@ -92,21 +109,40 @@ class OccupancyGridBasedCollisionDetector
92109
default;
93110
OccupancyGridBasedCollisionDetector & operator=(OccupancyGridBasedCollisionDetector &&) = delete;
94111
void setParam(const OccupancyGridMapParam & param) { param_ = param; };
95-
OccupancyGridMapParam getParam() const { return param_; };
112+
[[nodiscard]] OccupancyGridMapParam getParam() const { return param_; };
96113
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(
102124
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;
105135
virtual ~OccupancyGridBasedCollisionDetector() = default;
106136

107137
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
110146
{
111147
if (index.x < 0 || static_cast<int>(costmap_.info.width) <= index.x) {
112148
return true;
@@ -116,7 +152,7 @@ class OccupancyGridBasedCollisionDetector
116152
}
117153
return false;
118154
}
119-
inline bool isObs(const IndexXYT & index) const
155+
[[nodiscard]] inline bool is_obs(const IndexXYT & index) const
120156
{
121157
// NOTE: Accessing by .at() instead makes 1.2 times slower here.
122158
// Also, boundary check is already done in isOutOfRange before calling this function.
@@ -134,15 +170,7 @@ class OccupancyGridBasedCollisionDetector
134170

135171
// is_obstacle's table
136172
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_;
144173
};
145-
146174
} // namespace autoware::behavior_path_planner
147175

148176
#endif // AUTOWARE__BEHAVIOR_PATH_PLANNER_COMMON__UTILS__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR__OCCUPANCY_GRID_BASED_COLLISION_DETECTOR_HPP_

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp

+12-39
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ using autoware::universe_utils::createQuaternionFromYaw;
2525
using autoware::universe_utils::normalizeRadian;
2626
using autoware::universe_utils::transformPose;
2727

28-
int discretizeAngle(const double theta, const int theta_size)
28+
int discretize_angle(const double theta, const int theta_size)
2929
{
3030
const double one_angle_range = 2.0 * M_PI / theta_size;
3131
return static_cast<int>(std::rint(normalizeRadian(theta, 0.0) / one_angle_range)) % theta_size;
@@ -37,7 +37,7 @@ IndexXYT pose2index(
3737
{
3838
const int index_x = pose_local.position.x / costmap.info.resolution;
3939
const int index_y = pose_local.position.y / costmap.info.resolution;
40-
const int index_theta = discretizeAngle(tf2::getYaw(pose_local.orientation), theta_size);
40+
const int index_theta = discretize_angle(tf2::getYaw(pose_local.orientation), theta_size);
4141
return {index_x, index_y, index_theta};
4242
}
4343

@@ -68,18 +68,6 @@ geometry_msgs::msg::Pose global2local(
6868
return transformPose(pose_global, transform);
6969
}
7070

71-
geometry_msgs::msg::Pose local2global(
72-
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Pose & pose_local)
73-
{
74-
tf2::Transform tf_origin;
75-
tf2::convert(costmap.info.origin, tf_origin);
76-
77-
geometry_msgs::msg::TransformStamped transform;
78-
transform.transform = tf2::toMsg(tf_origin);
79-
80-
return transformPose(pose_local, transform);
81-
}
82-
8371
void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyGrid & costmap)
8472
{
8573
costmap_ = costmap;
@@ -105,7 +93,7 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG
10593
coll_indexes_table_.clear();
10694
for (int i = 0; i < param_.theta_size; i++) {
10795
std::vector<IndexXY> indexes_2d;
108-
computeCollisionIndexes(i, indexes_2d);
96+
compute_collision_indexes(i, indexes_2d);
10997
coll_indexes_table_.push_back(indexes_2d);
11098
}
11199
}
@@ -118,7 +106,7 @@ static IndexXY position2index(
118106
return {index_x, index_y};
119107
}
120108

121-
void OccupancyGridBasedCollisionDetector::computeCollisionIndexes(
109+
void OccupancyGridBasedCollisionDetector::compute_collision_indexes(
122110
int theta_index, std::vector<IndexXY> & indexes_2d)
123111
{
124112
IndexXYT base_index{0, 0, theta_index};
@@ -134,7 +122,7 @@ void OccupancyGridBasedCollisionDetector::computeCollisionIndexes(
134122
const auto base_theta = tf2::getYaw(base_pose.orientation);
135123

136124
// Convert each point to index and check if the node is Obstacle
137-
const auto addIndex2d = [&](const double x, const double y) {
125+
const auto add_index2d = [&](const double x, const double y) {
138126
// Calculate offset in rotated frame
139127
const double offset_x = std::cos(base_theta) * x - std::sin(base_theta) * y;
140128
const double offset_y = std::sin(base_theta) * x + std::cos(base_theta) * y;
@@ -149,14 +137,14 @@ void OccupancyGridBasedCollisionDetector::computeCollisionIndexes(
149137

150138
for (double x = back; x <= front; x += costmap_.info.resolution / 2) {
151139
for (double y = right; y <= left; y += costmap_.info.resolution / 2) {
152-
addIndex2d(x, y);
140+
add_index2d(x, y);
153141
}
154-
addIndex2d(x, left);
142+
add_index2d(x, left);
155143
}
156144
for (double y = right; y <= left; y += costmap_.info.resolution / 2) {
157-
addIndex2d(front, y);
145+
add_index2d(front, y);
158146
}
159-
addIndex2d(front, left);
147+
add_index2d(front, left);
160148
}
161149

162150
bool OccupancyGridBasedCollisionDetector::detectCollision(
@@ -175,27 +163,12 @@ bool OccupancyGridBasedCollisionDetector::detectCollision(
175163
coll_index.x += base_index.x;
176164
coll_index.y += base_index.y;
177165
if (check_out_of_range) {
178-
if (isOutOfRange(coll_index) || isObs(coll_index)) return true;
166+
if (is_out_of_range(coll_index) || is_obs(coll_index)) return true;
179167
} else {
180-
if (isOutOfRange(coll_index)) return false;
181-
if (isObs(coll_index)) return true;
182-
}
183-
}
184-
return false;
185-
}
186-
187-
bool OccupancyGridBasedCollisionDetector::hasObstacleOnPath(
188-
const geometry_msgs::msg::PoseArray & path, const bool check_out_of_range) const
189-
{
190-
for (const auto & pose : path.poses) {
191-
const auto pose_local = global2local(costmap_, pose);
192-
const auto index = pose2index(costmap_, pose_local, param_.theta_size);
193-
194-
if (detectCollision(index, check_out_of_range)) {
195-
return true;
168+
if (is_out_of_range(coll_index)) return false;
169+
if (is_obs(coll_index)) return true;
196170
}
197171
}
198-
199172
return false;
200173
}
201174

0 commit comments

Comments
 (0)