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

Revision history [back]

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>

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