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

Customize global costmap cost

asked 2018-03-19 00:16:32 -0500

timo1219520 gravatar image

updated 2018-03-22 04:32:46 -0500

Hello, I wan to customize my global costmap cost to control the path range of global planner,

I try to draw some pictures to descripte my question clearly as follows:

< pic 1. > The original global costmap with StaticLayer, ObstacleLayer(by laser scaner) and InflationLayer: image description

< pic 2. > The normal global path by global planner (global_planner/GlobalPlanner , dijkstra algo.): image description

< pic 3. > Customize the cost of global costmap, both of yellow and white field are FREE SPACE, but the cost of yellow is higher than white (the white field has the lowest valid cost): image description

< pic 4. > after adjust the cost of global costmap, one example path which generated by the global planner: image description

I already read the similar question before: Custom CostMap Values

But I don't need to change the cost dynamic, just one time when load the static global map.

  • in short

I need to let the global planner know:

##The white field is the best choice, but the yellow is still good.##

when planning a global path.

P.S. I also tried to edit the .pgm map file by GIMP, keep the white field color to 0xFEFEFE, and set yellow field color to 0xEEEEEE, but the behaviour of global planner was not changed.

From I know, the initialize of global map static layer convert the map value to only three types:

  • FREE_SPACE
  • LETHAL_OBSTACLE
  • NO_INFORMATION

If you can not understand my question because my poor English, I will explain it as clearly as I can.

Thanks for your help.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-03-19 11:48:08 -0500

David Lu gravatar image

The best way to do this is to edit the static map, which you tried, but can be tricky.

Using your altered image file, change the map.yaml to add mode: scale and make sure your occupied threshold is above 0.93 (0xEE / 0xFF). This should make it so that the map topic reflects your new map.

To get this properly read by the global planner, make sure that your static layer has trinary_costmap set to false. Documentation

(Your question made me realize the documentation was out of sync for the map_server, but I've updated it since.)

edit flag offensive delete link more

Comments

Dear David, forgive me for replying so late cause I think I need to to study as detail as possible. After referring to your answer and the source code, I achieved my goal successfully ,whether it the mode in RAW or SCALE. I have in depth comprehension about it right now, thank you very very much!

timo1219520 gravatar image timo1219520  ( 2018-03-22 02:05:04 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2018-03-19 00:16:32 -0500

Seen: 718 times

Last updated: Mar 22 '18