ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

how to edit costmap data manually?

asked 2013-06-12 03:05:31 -0500

Mohsen Hk gravatar image

updated 2014-01-28 17:16:52 -0500

ngrennan gravatar image

Hello :) i wanna edit costmap data manually. i have x and y location of map data given by hector_mapping. and my costmap_2d_ros_ data is runs ok like this:

costmap_2d_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tfl_);

how can i do?

costmap_2d::Costmap2D costmap_temp;
costmap_2d_ros_->getCostmapCopy(costmap_temp);

int map_width = costmap_temp.getSizeInCellsX();
int map_height = costmap_temp.getSizeInCellsY();
int num_map_cells = map_width * map_height;

const unsigned char* occupancy_grid_array;
occupancy_grid_array = costmap_temp.getCharMap();

geometry_msgs::PoseStamped lethal_obstacle;
point.pose.position.x=0.1;
point.pose.position.y=0.1;

if(??? QUESTION1 ???)
{
    ??? QUESTION2 ???=costmap_2d::LETHAL_OBSTACLE;
}

??? QUESTION3 ??? now convert costmap_2d::Costmap2D (costmap_temp) to costmap_2d::Costmap2DROS.
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2013-06-12 08:36:59 -0500

David Lu gravatar image

One solution is to format your incoming data as a PointCloud and go through existing channels for editing the costmap.

However, if you want to do it in code, you can edit the underlying charMap like this.

unsigned int mx, my;
costmap_temp.worldToMap(point.pose.position.x, point.pose.position.y, &mx, &my);
costmap_temp.setCost(mx, my, LETHAL_OBSTACLE);
edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-06-12 03:05:31 -0500

Seen: 845 times

Last updated: Jun 12 '13