Skip to content

Commit 4bb1022

Browse files
committed
Remove unorientFootprint function dependency
1 parent 0896059 commit 4bb1022

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

‎nav2_costmap_2d/src/costmap_topic_collision_checker.cpp‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -85,16 +85,16 @@ double CostmapTopicCollisionChecker::scorePose(
8585
return collision_checker_.footprintCost(getFootprint(pose));
8686
}
8787

88-
Footprint CostmapTopicCollisionChecker::getFootprint(const geometry_msgs::msg::Pose2D & pose)
88+
Footprint CostmapTopicCollisionChecker::getFootprint(const geometry_msgs::msg::Pose2D & /*pose*/)
8989
{
9090
Footprint footprint;
9191
if (!footprint_sub_.getFootprint(footprint)) {
9292
throw CollisionCheckerException("Current footprint not available.");
9393
}
9494

95-
Footprint footprint_spec;
96-
unorientFootprint(footprint, footprint_spec);
97-
transformFootprint(pose.x, pose.y, pose.theta, footprint_spec, footprint);
95+
// Footprint footprint_spec;
96+
// unorientFootprint(footprint, footprint_spec);
97+
// transformFootprint(pose.x, pose.y, pose.theta, footprint_spec, footprint);
9898

9999
return footprint;
100100
}

0 commit comments

Comments
 (0)