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

costmap clears obstacles when it should not

asked 2017-01-02 02:52:59 -0500

billy gravatar image

I have two sources for my costmap while running the navigation stack. A laser scanner and a pointcloud2 for bumper sensors. I have the costmap_common_params.yaml file set to clear the laser scanner but not the bumper. But it is clearing both. Actually, even when I set the laser to not clear, it also clears. So everything clears even when set to not clear.

Here is the costmap_common_params.yaml file.

obstacle_range: 2.5
raytrace_range: 5.0
footprint: [[-0.106, -0.106], [-0.106, 0.106], [0.106, 0.106], [0.150, 0], [0.106, -0.106]]
robot_radius: 0.150
inflation_radius: 0.3
transform_tolerance: 0.7

obstacle_layer:
  observation_sources: laser_scan_sensor bumper_sensor

  laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
  bumper_sensor: {sensor_frame: base_link, data_type: PointCloud2, topic: /pointcloud, marking: true, clearing: false}

I am using Jade on Ubuntu14.04.

I have tried two configurations, setting the point 'locations' of the bumper sensors far away when it is not activated, and set it at 0.0 when it is not activated. And then set just outside the edge of the robot when it is activated. The clearing behavior was the same regardless of where the points were located when the sensor isn't activated. The concept for moving the points far away came from this: http://docs.ros.org/kinetic/api/kobuk...

Can anyone suggest how to prevent the bumper sensor PointCloud2 obastacles from clearing from the cost map?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2017-01-02 15:49:21 -0500

billy gravatar image

updated 2017-01-02 16:32:12 -0500

I'll answer my own question: I found information here that helped me: http://wiki.ros.org/costmap_2d/Tutori...

My costmap_common_params.yaml file now looks like this and the bumper data is not being cleared.

obstacle_range: 2.5
raytrace_range: 5.0
footprint: [[-0.106, -0.106], [-0.106, 0.106], [0.106, 0.106], [0.150, 0], [0.106, -0.106]]
robot_radius: 0.150
inflation_radius: 0.3
transform_tolerance: 0.7

plugins:
  - {name: static_map, type: "costmap_2d::StaticLayer"}
  - {name: obstacles, type: "costmap_2d::VoxelLayer"}
  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

obstacles:
  observation_sources: laser_scan_sensor bumper_sensor

  laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
  bumper_sensor: {sensor_frame: base_link, data_type: PointCloud2, topic: /pointcloud, marking: true, clearing: false}

inflation_layer:
  enabled:              true
  cost_scaling_factor:  10.0  # exponential rate at which the obstacle cost drops off (default: 10)
  inflation_radius:     0.3  # max. distance from an obstacle at which costs are incurred for planning paths.
edit flag offensive delete link more
1

answered 2017-01-06 11:43:51 -0500

clyde gravatar image

The problem was that you were mixing pre-Hydro and post-Hydro configuration. Pre-Hydro the configuration was flat, so you shouldn't use the "obstacle_layer:" namespace. Post-Hydro everything moved to plug-ins, and the namespaces are required. This pre-Hydro configuration should also solve your original problem:

obstacle_range: 2.5
raytrace_range: 5.0
footprint: [[-0.106, -0.106], [-0.106, 0.106], [0.106, 0.106], [0.150, 0], [0.106, -0.106]]
robot_radius: 0.150
inflation_radius: 0.3
transform_tolerance: 0.7

observation_sources: laser_scan_sensor bumper_sensor

laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
bumper_sensor: {sensor_frame: base_link, data_type: PointCloud2, topic: /pointcloud, marking: true, clearing: false}
edit flag offensive delete link more

Comments

makes sense. Thanks for explaining.

billy gravatar image billy  ( 2017-01-07 12:46:55 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2017-01-02 02:52:59 -0500

Seen: 703 times

Last updated: Jan 06 '17