File tree 2 files changed +3
-3
lines changed
2 files changed +3
-3
lines changed Original file line number Diff line number Diff line change @@ -101,7 +101,7 @@ void transformFootprint(
101
101
* @param footprint A vector of points (type geometry_msgs::Point) representing a 2D polygon (footprint).
102
102
* @return The centroid of the footprint as a geometry_msgs::Point.
103
103
*/
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);
105
105
106
106
/* *
107
107
* @brief Given a pose and base footprint, build the oriented footprint of the robot (PolygonStamped)
Original file line number Diff line number Diff line change @@ -142,7 +142,7 @@ void transformFootprint(
142
142
}
143
143
}
144
144
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)
146
146
{
147
147
geometry_msgs::Point center;
148
148
double sum_x = 0.0 , sum_y = 0.0 ;
@@ -163,7 +163,7 @@ geometry_msgs::Point calculateCentroid(const std::vector<geometry_msgs::Point>&
163
163
164
164
void padFootprint (std::vector<geometry_msgs::msg::Point > & footprint, double padding)
165
165
{
166
- geometry_msgs::Point footprint_center = calculateCentroid (footprint);
166
+ geometry_msgs::msg:: Point footprint_center = calculateCentroid (footprint);
167
167
168
168
for (auto & point : footprint)
169
169
{
You can’t perform that action at this time.
0 commit comments