Skip to content

Commit 50f6542

Browse files
soblina-maumau
authored andcommitted
perf(behavior_path_planner_common): remove unnecessary angle calculation in OccupancyGridMapBasedDetector (autowarefoundation#7103)
perf(behavior_path_planner_common): unnecessary angle calculation in OccupancyGridMapBasedDetector Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 3778193 commit 50f6542

File tree

1 file changed

+12
-5
lines changed

1 file changed

+12
-5
lines changed

planning/behavior_path_planner_common/src/utils/occupancy_grid_based_collision_detector/occupancy_grid_based_collision_detector.cpp

+12-5
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,14 @@ void OccupancyGridBasedCollisionDetector::setMap(const nav_msgs::msg::OccupancyG
110110
}
111111
}
112112

113+
static IndexXY position2index(
114+
const nav_msgs::msg::OccupancyGrid & costmap, const geometry_msgs::msg::Point & position_local)
115+
{
116+
const int index_x = position_local.x / costmap.info.resolution;
117+
const int index_y = position_local.y / costmap.info.resolution;
118+
return {index_x, index_y};
119+
}
120+
113121
void OccupancyGridBasedCollisionDetector::computeCollisionIndexes(
114122
int theta_index, std::vector<IndexXY> & indexes_2d)
115123
{
@@ -131,12 +139,11 @@ void OccupancyGridBasedCollisionDetector::computeCollisionIndexes(
131139
const double offset_x = std::cos(base_theta) * x - std::sin(base_theta) * y;
132140
const double offset_y = std::sin(base_theta) * x + std::cos(base_theta) * y;
133141

134-
geometry_msgs::msg::Pose pose_local;
135-
pose_local.position.x = base_pose.position.x + offset_x;
136-
pose_local.position.y = base_pose.position.y + offset_y;
142+
geometry_msgs::msg::Point position_local;
143+
position_local.x = base_pose.position.x + offset_x;
144+
position_local.y = base_pose.position.y + offset_y;
137145

138-
const auto index = pose2index(costmap_, pose_local, param_.theta_size);
139-
const auto index_2d = IndexXY{index.x, index.y};
146+
const auto index_2d = position2index(costmap_, position_local);
140147
indexes_2d.push_back(index_2d);
141148
};
142149

0 commit comments

Comments
 (0)