Skip to content

Commit 797a28b

Browse files
mini-1235masf7g
authored andcommitted
Precompute yaw trigonometric values in smac planner (ros-navigation#5109)
Signed-off-by: mini-1235 <[email protected]>
1 parent f2faa6d commit 797a28b

File tree

1 file changed

+4
-2
lines changed

1 file changed

+4
-2
lines changed

nav2_smac_planner/include/nav2_smac_planner/utils.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -160,12 +160,14 @@ inline std::vector<geometry_msgs::msg::Point> transformFootprintToEdges(
160160
const double & x = pose.position.x;
161161
const double & y = pose.position.y;
162162
const double & yaw = tf2::getYaw(pose.orientation);
163+
const double sin_yaw = sin(yaw);
164+
const double cos_yaw = cos(yaw);
163165

164166
std::vector<geometry_msgs::msg::Point> out_footprint;
165167
out_footprint.resize(2 * footprint.size());
166168
for (unsigned int i = 0; i < footprint.size(); i++) {
167-
out_footprint[2 * i].x = x + cos(yaw) * footprint[i].x - sin(yaw) * footprint[i].y;
168-
out_footprint[2 * i].y = y + sin(yaw) * footprint[i].x + cos(yaw) * footprint[i].y;
169+
out_footprint[2 * i].x = x + cos_yaw * footprint[i].x - sin_yaw * footprint[i].y;
170+
out_footprint[2 * i].y = y + sin_yaw * footprint[i].x + cos_yaw * footprint[i].y;
169171
if (i == 0) {
170172
out_footprint.back().x = out_footprint[i].x;
171173
out_footprint.back().y = out_footprint[i].y;

0 commit comments

Comments
 (0)