Skip to content

Commit a19e736

Browse files
Support stamped footprints in costmap_2d
Signed-off-by: Sushant Chavan <gitecsvc@gmail.com>
1 parent dc92138 commit a19e736

File tree

5 files changed

+31
-19
lines changed

5 files changed

+31
-19
lines changed

nav2_costmap_2d/include/nav2_costmap_2d/costmap_2d_ros.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -313,7 +313,7 @@ class Costmap2DROS : public nav2::LifecycleNode
313313
* layered_costmap_->setFootprint(). Also saves the unpadded
314314
* footprint, which is available from
315315
* getUnpaddedRobotFootprint(). */
316-
void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon::SharedPtr footprint);
316+
void setRobotFootprintPolygon(const geometry_msgs::msg::Polygon & footprint);
317317

318318
std::shared_ptr<tf2_ros::Buffer> getTfBuffer() {return tf_buffer_;}
319319

@@ -351,6 +351,7 @@ class Costmap2DROS : public nav2::LifecycleNode
351351
std::vector<std::unique_ptr<Costmap2DPublisher>> layer_publishers_;
352352

353353
nav2::Subscription<geometry_msgs::msg::Polygon>::SharedPtr footprint_sub_;
354+
nav2::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_stamped_sub_;
354355
nav2::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr parameter_sub_;
355356

356357
// Dedicated callback group and executor for tf timer_interface and message filter
@@ -407,6 +408,8 @@ class Costmap2DROS : public nav2::LifecycleNode
407408
double transform_tolerance_{0}; ///< The timeout before transform errors
408409
double initial_transform_timeout_{0}; ///< The timeout before activation of the node errors
409410
double map_vis_z_{0}; ///< The height of map, allows to avoid flickering at -0.008
411+
/// If true, the footprint subscriber expects a PolygonStamped msg
412+
bool subscribe_to_stamped_footprint_{false};
410413

411414
bool is_lifecycle_follower_{true}; ///< whether is a child-LifecycleNode or an independent node
412415

nav2_costmap_2d/include/nav2_costmap_2d/footprint.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -65,23 +65,23 @@ std::pair<double, double> calculateMinAndMaxDistances(
6565
/**
6666
* @brief Convert Point32 to Point
6767
*/
68-
geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt);
68+
geometry_msgs::msg::Point toPoint(const geometry_msgs::msg::Point32 & pt);
6969

7070
/**
7171
* @brief Convert Point to Point32
7272
*/
73-
geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt);
73+
geometry_msgs::msg::Point32 toPoint32(const geometry_msgs::msg::Point & pt);
7474

7575
/**
7676
* @brief Convert vector of Points to Polygon msg
7777
*/
78-
geometry_msgs::msg::Polygon toPolygon(std::vector<geometry_msgs::msg::Point> pts);
78+
geometry_msgs::msg::Polygon toPolygon(const std::vector<geometry_msgs::msg::Point> & pts);
7979

8080
/**
8181
* @brief Convert Polygon msg to vector of Points.
8282
*/
8383
std::vector<geometry_msgs::msg::Point> toPointVector(
84-
geometry_msgs::msg::Polygon::SharedPtr polygon);
84+
const geometry_msgs::msg::Polygon & polygon);
8585

8686
/**
8787
* @brief Given a pose and base footprint, build the oriented footprint of the robot (list of Points)

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,7 @@ void Costmap2DROS::init()
133133
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
134134
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
135135
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
136+
declare_parameter("subscribe_to_stamped_footprint", rclcpp::ParameterValue(false));
136137
}
137138

138139
Costmap2DROS::~Costmap2DROS()
@@ -218,9 +219,15 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
218219
}
219220

220221
// Create the publishers and subscribers
221-
footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
222-
"footprint",
223-
std::bind(&Costmap2DROS::setRobotFootprintPolygon, this, std::placeholders::_1));
222+
if (subscribe_to_stamped_footprint_) {
223+
footprint_stamped_sub_ = create_subscription<geometry_msgs::msg::PolygonStamped>(
224+
"footprint", [this](const geometry_msgs::msg::PolygonStamped::SharedPtr footprint)
225+
{setRobotFootprintPolygon(footprint->polygon);});
226+
} else {
227+
footprint_sub_ = create_subscription<geometry_msgs::msg::Polygon>(
228+
"footprint", [this](const geometry_msgs::msg::Polygon::SharedPtr footprint)
229+
{setRobotFootprintPolygon(*footprint);});
230+
}
224231

225232
footprint_pub_ = create_publisher<geometry_msgs::msg::PolygonStamped>(
226233
"published_footprint");
@@ -415,6 +422,7 @@ Costmap2DROS::getParameters()
415422
get_parameter("width", map_width_meters_);
416423
get_parameter("plugins", plugin_names_);
417424
get_parameter("filters", filter_names_);
425+
get_parameter("subscribe_to_stamped_footprint", subscribe_to_stamped_footprint_);
418426

419427
auto node = shared_from_this();
420428

@@ -483,7 +491,7 @@ Costmap2DROS::setRobotFootprint(const std::vector<geometry_msgs::msg::Point> & p
483491

484492
void
485493
Costmap2DROS::setRobotFootprintPolygon(
486-
const geometry_msgs::msg::Polygon::SharedPtr footprint)
494+
const geometry_msgs::msg::Polygon & footprint)
487495
{
488496
setRobotFootprint(toPointVector(footprint));
489497
}

nav2_costmap_2d/src/footprint.cpp

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ std::pair<double, double> calculateMinAndMaxDistances(
7171
return std::pair<double, double>(min_dist, max_dist);
7272
}
7373

74-
geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt)
74+
geometry_msgs::msg::Point32 toPoint32(const geometry_msgs::msg::Point & pt)
7575
{
7676
geometry_msgs::msg::Point32 point32;
7777
point32.x = pt.x;
@@ -80,7 +80,7 @@ geometry_msgs::msg::Point32 toPoint32(geometry_msgs::msg::Point pt)
8080
return point32;
8181
}
8282

83-
geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
83+
geometry_msgs::msg::Point toPoint(const geometry_msgs::msg::Point32 & pt)
8484
{
8585
geometry_msgs::msg::Point point;
8686
point.x = pt.x;
@@ -89,20 +89,22 @@ geometry_msgs::msg::Point toPoint(geometry_msgs::msg::Point32 pt)
8989
return point;
9090
}
9191

92-
geometry_msgs::msg::Polygon toPolygon(std::vector<geometry_msgs::msg::Point> pts)
92+
geometry_msgs::msg::Polygon toPolygon(const std::vector<geometry_msgs::msg::Point> & pts)
9393
{
9494
geometry_msgs::msg::Polygon polygon;
95-
for (unsigned int i = 0; i < pts.size(); i++) {
96-
polygon.points.push_back(toPoint32(pts[i]));
95+
polygon.points.reserve(pts.size());
96+
for (const auto & pt : pts) {
97+
polygon.points.push_back(toPoint32(pt));
9798
}
9899
return polygon;
99100
}
100101

101-
std::vector<geometry_msgs::msg::Point> toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
102+
std::vector<geometry_msgs::msg::Point> toPointVector(const geometry_msgs::msg::Polygon & polygon)
102103
{
103104
std::vector<geometry_msgs::msg::Point> pts;
104-
for (unsigned int i = 0; i < polygon->points.size(); i++) {
105-
pts.push_back(toPoint(polygon->points[i]));
105+
pts.reserve(polygon.points.size());
106+
for (const auto & point : polygon.points) {
107+
pts.push_back(toPoint(point));
106108
}
107109
return pts;
108110
}

nav2_costmap_2d/src/footprint_subscriber.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,7 @@ FootprintSubscriber::getFootprintRaw(
3535
}
3636

3737
auto current_footprint = std::atomic_load(&footprint_);
38-
footprint = toPointVector(
39-
std::make_shared<geometry_msgs::msg::Polygon>(current_footprint->polygon));
38+
footprint = toPointVector(current_footprint->polygon);
4039
footprint_header = current_footprint->header;
4140

4241
return true;

0 commit comments

Comments
 (0)