0
$\begingroup$

Rosanswers logo

Hi,
I have the ROS navigation stack running on a robot. I can choose a point in RVIZ for the robot to navigate to and it is working well, except for sometimes the robot will start doing clearing rotations because it can't find a route through the global map. I then check the global map and see that obstacles have been put into it even though I have it set to be a static map.

Also in RVIZ the global map sometimes doesn't update until I toggle it off and back on again.

Here is my global_costmap_params.yaml

global_costmap:
  global_frame: /map
  robot_base_frame: base_link
  update_frequency: 5.0
  static_map: true

And here is the part of my launch files that loads move_base

<node pkg="move_base" type="move_base" name="move_base" >
    <rosparam file="$(find goose_chaser_main)/move_base_config/costmap_common_params.yaml" command="load" ns="global_costmap" />
    <rosparam file="$(find goose_chaser_main)/move_base_config/costmap_common_params.yaml" command="load" ns="local_costmap" />
    <rosparam file="$(find goose_chaser_main)/move_base_config/local_costmap_params.yaml" command="load" />
    <rosparam file="$(find goose_chaser_main)/move_base_config/global_costmap_params.yaml" command="load" />
    <rosparam file="$(find goose_chaser_main)/move_base_config/base_local_planner_params.yaml" command="load" />
</node>

Also is there a way to verify that my .yaml file is being loaded?

Update:
I verified that the .yaml file is indeed being loaded by running

rosparam get /move_base/global_costmap/static_map

Which returned: true

Update 2

I am running move_base with the default recovery behavior which includes clear_costmap_recovery, so I'm confused at why this recovery isn't working

Here is a picture of a situation where my robot failed to find a valid plan image description

Update 3

Here are my config files:

base_local_planner_params.yaml
local_costmap_params.yaml
global_costmap_params.yaml
costmap_common_params.yaml


Originally posted by shoemakerlevy9 on ROS Answers with karma: 545 on 2017-01-20

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

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"]

Originally posted by Procópio with karma: 4402 on 2017-02-01

This answer was ACCEPTED on the original site

Post score: 5


Original comments

Comment by shoemakerlevy9 on 2017-03-01:
Thank you, your answer helped me to better understand whats going on, but things are still not working. I'm using a stereo camera which is very noisy. Many erroneous objects are entering my global map. I'm running with default recovery but these objects dont get removed by clear_costmap_recovery

Comment by shoemakerlevy9 on 2017-03-01:
So I have 2 follow up questions. How can I prevent erroneous objects from entering my global costmap in the first place and why might aren't these objects being cleared by clear_costmap_recovery?

Comment by Procópio on 2017-03-06:\

  1. you can try filtering them.
  2. try this command rosservice call /move_base/clear_costmaps "{}" . if it works, you are probably missing something in the config of your recovery behaviors. can you post your config please?

Comment by shoemakerlevy9 on 2017-03-06:
That worked.

Comment by shoemakerlevy9 on 2017-03-06:
By the way, I have been putting general move_base params in base_local_planner_params.yaml for lack of a better place to put them. Is there a convention for where to put them? Where do you put them?

Comment by Procópio on 2017-03-09:
you can put it all in the same file or split one for move_base, other for recovery, etc... it is up to you. what matters is the structure and namespace of the yamls you are using.

Comment by shoemakerlevy9 on 2017-03-13:
So since I can call /move_base/clear_costmaps manually but my recovery sequence doesn't work it seems it may be mis-configured. Do any of my config parameters seem off? I have triple checked them all and they seem right to me.

Comment by Procópio on 2017-03-15:
I edited my answer with more info about what can be wrong.

Comment by shinyH on 2021-05-15:
Thanks, changing the layer name accordingly has fixed my problems.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.