(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

How to set up hector_slam for your robot

Description: This tutorial shows you how to set frame names and options for using hector_slam with different robot systems.

Tutorial Level: BEGINNER

Overview

hector_slam uses the hector_mapping node for learning a map of the environment and simultaneously estimating the platform's 2D pose at laser scanner frame rate. The frame names and options for hector_mapping have to be set correctly. This tutorial explains the different options. The image below shows all potential frames of interest in a simplified 2D view of a robot travelling through rough terrain, leading to roll and pitch motion of the platform:

attachment:coordsystems_img.png

The general relationship between the map, odom and base_link frames is already described in Coordinate Frames for Mobile Platforms. We use two frames in between odom and base_link: The base_footprint frame provides no height information and represents the 2D pose of the robot (position and orientation). The base_stabilized frame adds information about the robot height relative to the map/odom layer. The base_link frame is rigidly attached to the robot and adds the roll and pitch angles compared to the base_stabilized frame. For this transformation, a system for estimation of the vehicle attitude like a AHRS or INS can be used (can be realized using the hector_imu_attitude_to_tf node for example). For a platform not exhibiting roll/pitch motion, the base_stabilized and base_link frames are equal. The transformation from base_link to laser_link is typically provided by a static transform publisher or the robot state publisher.

Setup

We assume that the reader has a basic understanding of ROS parameters and launch files for the following section. The hector_slam_launch package contains some launch files that might serve as examples.

Use in place of gmapping

gmapping publishes the map->odom transform. You have to set the following parameters of hector_mapping to reflect the setup on your platform:

    <param name="pub_map_odom_transform" value="true"/>
    <param name="map_frame" value="map" />
    <param name="base_frame" value="base_frame" />
    <param name="odom_frame" value="odom" />

If your platform exhibits roll/pitch motion you have to set the base_frame so it has the properties of the base_stabilized frame described in the Overview section above.

Use without odom frame

If you do not require the use of a odom frame (for example because your platform does not provide any usable odometry) you can directly publish a transformation from map to base_link:

    <param name="pub_map_odom_transform" value="true"/>
    <param name="map_frame" value="map" />
    <param name="base_frame" value="base_frame" />
    <param name="odom_frame" value="base_frame" />

Use without Broadcasting of transformations

The system can also be used without broadcasting any tf transformation. This can be useful if another node is responsible for publishing the map->odom or map->base_frame transform. This can be done by setting:

    <param name="pub_map_odom_transform" value="false"/>

In this case, the estimated pose published on the poseupdate topic of hector_mapping might be used for example by a INS system which then publishes a map->base_frame transform.

Wiki: hector_slam/Tutorials/SettingUpForYourRobot (last edited 2012-08-31 10:57:31 by StefanKohlbrecher)