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

costmap_2d::VoxelLayer not clearing [closed]

asked 2014-11-18 08:05:48 -0500

Federico gravatar image

Hello there,

I'm using the move_base navigation stack. I'm realizing that the costmap_2d::VoxelLayer doesn't seem to clear up the costmap when the data are fed from and rgbd sensor. I'm using the following costmap configuration (I omit the local_costmap and global_costmap parameters, I report only the common parameters)

robot_radius: 0.16
plugins:
  - {name: static_layer, type: 'costmap_2d::StaticLayer'}
  - {name: obstacles_layer, type: "costmap_2d::VoxelLayer"}
  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

obstacles_layer:
  obstacle_range: 1.5
  raytrace_range: 3.0
  observation_sources: rgbd_scan laser_scan 
  rgbd_scan: {sensor_frame: camera_rgb_optical_frame, data_type: PointCloud2, topic: rgbdscan, marking: true, clearing: true, min_obstacle_height: 0.03, max_obstacle_height: 1.00, mark_threshold: 3}
  laser_scan: {sensor_frame: laser_link, data_type: LaserScan, topic: scan, marking: true, clearing: true} 

inflation_layer: 
  inflation_radius: 0.7
  cost_scaling_factor: 20.0

Clearing doesn't work!

Regards, Federico

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Procópio
close date 2016-01-27 08:21:24.541430

1 Answer

Sort by » oldest newest most voted
1

answered 2014-11-20 10:43:12 -0500

Federico gravatar image

Hello,

After studying the code of costmap_2d::VoxelLayer I found the reason why.

Apparently, the clearing strategy implemented in the VoxelLayer works fine, however, when the points in the clouds that don't lie in the range min/max_obstacle_range are removed from the observation set so, for instance, if you set a min_obstacle_height to filter the floor, the observation of the floor are removed and no clearing is applied.

edit flag offensive delete link more

Comments

1

We circumvented that by adding the rgb_scan twice as observation source. One with marking which has a min_obstacle_height heigher than the floor. The other one with only clearing which has a min_bstacle_height lower than the floor

AReimann gravatar image AReimann  ( 2014-11-25 01:37:54 -0500 )edit

Thanks for your suggestion. I'll try it but I think that the VoxelLayer now treats each observation independently so that clearing and marking are applied to each observation source without affecting the others. Anyway, I can be wrong.

Federico gravatar image Federico  ( 2014-11-25 03:03:25 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2014-11-18 08:05:48 -0500

Seen: 1,093 times

Last updated: Nov 20 '14