0
$\begingroup$

Rosanswers logo

Hi,

i am trying to get a rolling window global costmap. I know that this is highly uncommon, but in my usecase it would be extremely beneficial if the global costmap wouldn't keep anything for ever. (This is for a robot on Street Loop with potential obstacles). As you can see in the picture the border of the global costmap gets marked as an obstacle and isn't removed by the next update. https://imgur.com/g2p3106 It gets only partly removed once cost values of the local map are close to the previous borders of the global one.

I tried setting allways send full cost map to true but that didn't change anything

I would be extremely grateful for any help or tips, thanks in advance Tristan

The config file of the global costmap is as follows:

global_costmap:
   map_type: costmap
   global_frame: map
  
   robot_base_frame: base_footprint
   update_frequency: 5.0
   publish_frequency: 5.0
   
   static_map: false
   rolling_window: true
   always_send_full_costmap: true
   
   width: 10.0
   height: 10.0

      - {name: obstacle_layer,    type: "costmap_2d::ObstacleLayer"}
      - {name: inflation_layer, type: "costmap_2d::InflationLayer"}

Originally posted by Tristan9497 on ROS Answers with karma: 220 on 2021-02-11

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

I just was able to solve this myself.

For future readers:

This behaviour isn't caused by the costmaps themselves, but by the global_planner of the navigation stack. To fix this you'll need to set its parameter outline_map to false which is by default set to true. This isn't included in the parameter @ http://wiki.ros.org/global_planner#Parameters and i am unsure if you can set it directly from the launch file.

I changed the default value in the planner_core.cpp file located at navigation/global_planner/src/planner_core.cpp at line 149, which definitely isn't the cleanest way possible.

If you configured this you'll be able to use a rolling window for global maps aswell.

This Parameter has been added by the following PR see the following commit for details:

https://github.com/ros-planning/navigation/commit/57c3cb2357201e956be80324bb9b9282ff0fa051

EDIT:

If someone can change it in the ros wiki please do

EDIT:

i just added i to the wiki. Unfortunately i can't accept this answer myself


Originally posted by Tristan9497 with karma: 220 on 2021-02-11

This answer was ACCEPTED on the original site

Post score: 0

$\endgroup$

Your Answer

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