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

How to get a collision-free path in a known map with move_base?

asked 2018-07-20 09:25:30 -0500

Hug gravatar image

updated 2018-07-25 06:47:50 -0500

Hi everyone,

I would like to use the global planner only to compute a collision-free path from pose A to pose B for a rectangular robot from a .png map (To be precise, I mean a nav_msgs/Path Message). I ran a map server using:

rosrun map_server map_server map.yml

where map.yml is:

image: 1st_Floor.png
resolution: 0.1
origin: [0.0, 0.0, 0.0]
occupied_thresh: 0.65
free_thresh: 0.196
negate: 0

I used the information on this page: http://wiki.ros.org/map_server. Now I would like map_server to publish on a global_costmap, as shown there: http://wiki.ros.org/move_base, which in turn should publish on a global_planner. I don't really understand how to initialize costmap_2d and global_planner and what other things I should do.

Can anybody tell me what I am supposed to do? Basically, I would like to do something similar to what is shown on the global_planner documentation page.

[EDIT]

I tried David Lu's answer:

1st console:

roslauch my_planner.launch

2nd console:

rosrun map_server map_server map.yml

Finally, I get:

1st console:

...
[ INFO] [1532441256.591719189]: Using plugin "static_layer"
[ INFO] [1532441256.603717786]: Requesting the map...
[ INFO] [1532441410.809228149]: Resizing costmap to 942 X 850 at 0.100000 m/pix
[ INFO] [1532441410.908177209]: Received a 942 X 850 map at 0.100000 m/pix

2nd console:

[ INFO] [1532441410.480988502]: Loading map from image "./1st_Floor.png"
[ INFO] [1532441410.500530096]: Read a 942 X 850 map @ 0.100 m/cell

It seems OK but when I use rosservice call /gp/make_plan "...", I get the following error:

ERROR: transport error completing service call: unable to receive data from sender, check sender's logs for details

and in 1st console:

[gp-2] process has died [pid 14912, exit code -11, cmd /opt/ros/kinetic/lib/global_planner/planner __name:=gp __log:=/home/loic/.ros/log/5cecac24-8f4e-11e8-83cf-843a4b9cdf04/gp-2.log].

[EDIT 2]

I tried with a white map to be sure that the start and goal poses are on the map but that didn't work, so I think something is missing for the planner to work properly. Any idea?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-07-23 14:55:34 -0500

David Lu gravatar image

updated 2018-07-27 15:45:14 -0500

You can use the planner node included with the global_planner package to do this.

Here's a launch file:

<launch>
  <node name="gp" pkg="global_planner" type="planner" output="screen">
  <rosparam>
  costmap:
    plugins:
      - {name: 'static_layer', type: 'costmap_2d::StaticLayer'}
  </rosparam>
  </node>
  <node name="static_tf" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 /map /base_link 100"/>
</launch>

This provides the navfn::MakePlan service which you can call like this:

rosservice call /gp/make_plan "start:
  header:
    seq: 0
    stamp:
      secs: 0
      nsecs: 0
    frame_id: '/map'
  pose:
    position:
      x: 1.0
      y: 1.0
      z: 0.0
    orientation:
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0
goal:
  header:
    seq: 0
    stamp:
      secs: 0
      nsecs: 0
    frame_id: '/map'
  pose:
    position:
      x: 5.0
      y: 1.0
      z: 0.0
    orientation:
      x: 0.0
      y: 0.0
      z: 0.0
      w: 1.0"
edit flag offensive delete link more

Comments

Thanks for the answer. I ran the launch file you gave me and then the map server and it seemed to work but when I call the service I get an error. I edited the question.

Hug gravatar image Hug  ( 2018-07-24 09:43:32 -0500 )edit

Did you send it coordinates inside your map?

David Lu gravatar image David Lu  ( 2018-07-24 09:49:48 -0500 )edit

I'm not really sure how the coordinates work (cells, pixel, ...), so I don't know how to get valid poses. So I just tried with a 942x850 completely white image. I gave the same coordinates as you did and got the same error.

Hug gravatar image Hug  ( 2018-07-24 10:33:24 -0500 )edit

What happens if you change the start x position to 1.0?

David Lu gravatar image David Lu  ( 2018-07-24 10:35:24 -0500 )edit

It displays the same error. Have you been able to run it?

Hug gravatar image Hug  ( 2018-07-24 10:40:59 -0500 )edit

I've duplicated your blank map and changed the coordinates above to reflect valid coordinates. There's some weird stuff with the hard coded frame_ids in the melodic version of the plan_node, but other than that, it works fine.

David Lu gravatar image David Lu  ( 2018-07-27 15:46:32 -0500 )edit

Thanks, sorry for the late reply, I was very busy. I changed the coordinates and it works. Now I'm wondering: how can I change the dimensions of my robot? I have currently no idea of when my robot is considered to be in collision with an obstacle on the map.

Hug gravatar image Hug  ( 2018-08-01 10:31:48 -0500 )edit
1

Excellent! Please mark this question as correct with the checkmark to the left.

You should check out http://wiki.ros.org/costmap_2d#Inflation for more info on changing the dimensions, and if you have further questions, open a new question here. Best of luck!

David Lu gravatar image David Lu  ( 2018-08-01 10:37:34 -0500 )edit

Question Tools

Stats

Asked: 2018-07-20 09:25:30 -0500

Seen: 499 times

Last updated: Jul 27 '18