[ros-users] costmap_2d::Costmap2DROS map topic parameter (ti…

Top Page
Attachments:
Message as email
+ (text/plain)
+ (text/html)
+ costmap2d-map_topic.diff (text/plain)
Delete this message
Reply to this message
Author: User discussions
Date:  
To: ros-users
Subject: [ros-users] costmap_2d::Costmap2DROS map topic parameter (ticket 4497)
Hello.

This is a duplicate of Ticket # 4497
After looking over the other tickets I wasn't sure anymore, if my patch
would belong there, so I decided to repost it here.
Please duely reprimand me if I violated any policies :)

https://code.ros.org/trac/ros-pkg/ticket/4497 reads:

//snip

For my project I needed the Costmap2DROS wrapper to listen to a
different map topic than the hardcoded "map" one. I added an optional
parameter (in(for) the configuration file) and found the change to be
minimally invasive and quite useful. So I thought I'd share it.

The patch (against boxturtle r28817
<https://code.ros.org/trac/ros-pkg/changeset/28817> but also applicable
on cturtle ) is attached.

//unsnip

I attached the patch file to this message.

Hope you find this useful, too.

Best regards,
Andreas Tropschug
Index: src/costmap_2d_ros.cpp
===================================================================
--- src/costmap_2d_ros.cpp    (revision 29409)
+++ src/costmap_2d_ros.cpp    (working copy)
@@ -188,11 +188,13 @@
     private_nh.param("rolling_window", rolling_window_, false);


     double map_width_meters, map_height_meters;
+    std::string map_topic;
     private_nh.param("width", map_width_meters, 10.0);
     private_nh.param("height", map_height_meters, 10.0);
     private_nh.param("resolution", map_resolution, 0.05);
     private_nh.param("origin_x", map_origin_x, 0.0);
     private_nh.param("origin_y", map_origin_y, 0.0);
+    private_nh.param("map_topic", map_topic, std::string("map"));
     map_width = (unsigned int)(map_width_meters / map_resolution);
     map_height = (unsigned int)(map_height_meters / map_resolution);


@@ -201,7 +203,7 @@
       ros::NodeHandle g_nh;


       ROS_INFO("Requesting the map...\n");
-      map_sub_ = g_nh.subscribe("map", 1, &Costmap2DROS::incomingMap, this);
+      map_sub_ = g_nh.subscribe(map_topic.c_str(), 1, &Costmap2DROS::incomingMap, this);


       ros::Rate r(1.0);
       while(!map_initialized_ && ros::ok()){