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

Combining laser_scan_matcher with gmapping

asked 2011-08-15 19:57:12 -0600

tom gravatar image

updated 2011-08-17 09:54:30 -0600

Hi,

I'm having hard time trying to set up a SLAM system with a laser scanner using gmapping. I installed laser_drivers, scan_tools and slam_gmapping stacks. I'm having no problems with laser_scan_matcher. I'm using the following launchfile for laser_scan_matcher and hokuyo_node:

Deleted to avoid confusion, look at Ivan's answer below instead

So so far I've got:

  • a hokuyo_node publishing scans on a /scan topic
  • a laser_scan_matcher publishing odometry tf on /base_link tf
  • a tf tree set up as follows: laser -> base_link -> world (I don't actually know what the laser tf is here for, but it's been there in an example, so it stays for now)

What should my call to gmapping look like for the connection to laser_scan_matcher to work? Of course I tried a lot but none of the calls / launchfiles worked so I think it's best to ask an open question here first.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
3

answered 2011-08-16 00:09:58 -0600

dornhege gravatar image

gmapping needs odometry as /odom -> /base_link. Setting the ~fixed_frame parameter from world to odom in the laser_scan_matcher should provide that. In this way the laser_scan_matcher should provide fake odometry by scanmatching. Alternately you can set the ~odom_frame parameter in gmapping to world (only do one of these).

If you run gmapping now it should work.

The base_link -> laser transform gives the position of the laser relative to your robot. As you are passing 0 0 0, your are saying its in the center of the robot. You should adjust that to the real position of the laser.

edit flag offensive delete link more

Comments

Setting ~fixed_frame to odom and running gmapping with: rosrun gmapping slam_gmapping scan:=scan helped, thanks. I also tried running: rosrun gmapping slam_gmapping scan:=scan odom_frame:=world, but this didn't work because of missing transforms between world, base_link, laser and map.
tom gravatar image tom  ( 2011-08-16 01:39:07 -0600 )edit
1
I think a tutorial about using gmapping with laser_scan_matcher would be a big help to many here, so if anyone could come up with one, it would be great.
tom gravatar image tom  ( 2011-08-16 01:45:24 -0600 )edit
To set the odom_frame in gmapping, the cmd line should be _odom_frame:=world (note the leading _) as it sets a private parameter (noted ~... in the docs). You can leave the scan:=scan remapping as it changes nothing.
dornhege gravatar image dornhege  ( 2011-08-16 02:11:32 -0600 )edit
Right, edited my question to avoid confusion. Thank you.
tom gravatar image tom  ( 2011-08-16 03:48:28 -0600 )edit
4

answered 2011-08-17 04:15:31 -0600

updated 2011-08-17 04:20:07 -0600

Hi Tom,

Sorry for not replying earlier - it looks like you might have it figured out already. I agree a tutorial would be very useful, and I'll work on putting one up.

In the meantime, here is a launch file to get you started. It uses the same recorded bag file that is in the laser_scan_matcher/demo directory. I will include it in the next release of laser_scan_matcher.

The only key thing that needs to be changed to pass the correct fixed_frame parameter to laser_scan_matcher.

<param name="fixed_frame" value = "odom"/>

This lets laser_scan_matcher publish it's f between odom and base_link (instead of world and base_link). Everything else should work out of the box.

<launch>

  <param name="/use_sim_time" value="true"/>

  <node pkg="tf" type="static_transform_publisher" name="base_link_to_laser" 
   args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /laser 40" />

  <node pkg="rviz" type="rviz" name="rviz"/>

  <node pkg="rosbag" type="rosbag" name="rosbag" 
    args="play $(find laser_scan_matcher)/demo/demo.bag --delay=5 --clock"/>

  <node pkg="laser_scan_matcher" type="laser_scan_matcher_node" 
    name="laser_scan_matcher_node" output="screen">
    <param name="fixed_frame" value = "odom"/>
    <param name="use_alpha_beta" value="true"/>
    <param name="max_iterations" value="10"/>
  </node>

  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
    <param name="map_udpate_interval" value="1.0"/>
    <param name="delta" value="0.02"/>
  </node>

</launch>

EDIT:

I noticed the launch file you posted is very similar, but you told gmapping to use the world frame as it's odometry frame. While this will work, it is cleaner to go about it the way I suggested. The way you have it, the tf chain is:

odom --> world --> base_link

The correct chain, as suggested by the ROS REP on coordinate frames, should be:

world --> odom --> base_link

edit flag offensive delete link more

Comments

1
Yes, that seems like a cleaner solution. I think @tom's has map->world->base_link and with your's will get map->odom->base_link.
dornhege gravatar image dornhege  ( 2011-08-17 05:27:55 -0600 )edit
@dornhege Yes I think you're right - my bad.
Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2011-08-17 05:49:42 -0600 )edit
Thanks Ivan. A tutorial will be great as is laser_scan_matcher itself.
tom gravatar image tom  ( 2011-08-17 09:52:56 -0600 )edit

@tom Is there document / tutorial available for combing laser_scan_matcher and gmapping?

tsdk00 gravatar image tsdk00  ( 2019-07-28 03:15:04 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2011-08-15 19:57:12 -0600

Seen: 13,060 times

Last updated: Aug 17 '11