ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
If you are using the clear_costmap_recovery
, that is what is expected to happen. It will basically reset the costmap of new marking/clearing done with your sensors, up until a distance from the robot. That means you are left with the original map in the reseted zones.
You can remove the clear_costmap_recovery
and stay only with the rotate_recovery
, where this issue will not happen.
2 | No.2 Revision |
If you are using the clear_costmap_recovery
, that is what is expected to happen. It will basically reset the costmap of new marking/clearing done with your sensors, up until a distance from the robot. That means you are left with the original map in the reseted zones.zones. Check the wiki.
You can remove the clear_costmap_recovery
and stay only with the rotate_recovery
, where this issue will not happen.
3 | No.3 Revision |
If you are using the clear_costmap_recovery
, that is what is expected to happen. It will basically reset the costmap of new marking/clearing done with your sensors, up until a distance from the robot. That means you are left with the original map in the reseted zones. Check the wiki.
You can remove the clear_costmap_recovery
and stay only with the rotate_recovery
, where this issue will not happen.
EDIT
what is happening is that the clear_costmap_recovery will clean the layers specified in its config file (which by default is "obstacles"). BUT you are using a legacy costmap config (and an incomplete one), which creates a layer called obstacle_layer, so that is the reason it is not working.
You can either update your costmap config to the new layered form, or change the config of your recovery to clean the correct layer.
Option 1: Try changing your costmap_common_params
to something like this:
obstacle_range: 8.0
raytrace_range: 8.0
footprint: [ [0.4, 0.25], [-0.4, 0.25], [-0.4, -0.25], [0.4, -0.25] ]
inflation_radius: 0.2
plugins:
- name: obstacles
type: "costmap_2d::ObstacleLayer"
obstacles:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: zed_link, data_type: LaserScan, topic: scan, marking: true, clearing: true}
it still looks incomplete, but you may get what you want from the recovery behavior. more info here: http://wiki.ros.org/costmap_2d/Tutorials/Configuring%20Layered%20Costmaps
Option 2: Specify what layer you want to clear, updating the config file of your recovery behaviors to something like this:
recovery_behaviors:
- name: 'costmap_reset_conservative'
type: 'clear_costmap_recovery/ClearCostmapRecovery'
costmap_reset_conservative:
reset_distance: 1.5
layer_names: ["obstacle_layer"]