Skip to content

Commit e621d5f

Browse files
committed
fix code not building
1 parent a1a78a3 commit e621d5f

File tree

2 files changed

+3
-3
lines changed

2 files changed

+3
-3
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ void transformFootprint(
101101
* @param footprint A vector of points (type geometry_msgs::Point) representing a 2D polygon (footprint).
102102
* @return The centroid of the footprint as a geometry_msgs::Point.
103103
*/
104-
geometry_msgs::Point calculateCentroid(const std::vector<geometry_msgs::Point>& footprint);
104+
geometry_msgs::msg::Point calculateCentroid(const std::vector<geometry_msgs::msg::Point>& footprint);
105105

106106
/**
107107
* @brief Given a pose and base footprint, build the oriented footprint of the robot (PolygonStamped)

nav2_costmap_2d/src/footprint.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ void transformFootprint(
142142
}
143143
}
144144

145-
geometry_msgs::Point calculateCentroid(const std::vector<geometry_msgs::Point>& footprint)
145+
geometry_msgs::msg::Point calculateCentroid(const std::vector<geometry_msgs::msg::Point>& footprint)
146146
{
147147
geometry_msgs::Point center;
148148
double sum_x = 0.0, sum_y = 0.0;
@@ -163,7 +163,7 @@ geometry_msgs::Point calculateCentroid(const std::vector<geometry_msgs::Point>&
163163

164164
void padFootprint(std::vector<geometry_msgs::msg::Point> & footprint, double padding)
165165
{
166-
geometry_msgs::Point footprint_center = calculateCentroid(footprint);
166+
geometry_msgs::msg::Point footprint_center = calculateCentroid(footprint);
167167

168168
for (auto& point : footprint)
169169
{

0 commit comments

Comments
 (0)