Only released in EOL distros:  

Package Summary

The ohm_tsd_slam package provides a 2D SLAM approach for laser scanners.

  • Maintainer: Philipp Koch <philipp.koch AT th-nuernberg DOT de>, Markus Kühn <markus.kuehn AT th-nuernberg DOT de>
  • Author: Philipp Koch, Stefan May, Markus Kühn
  • License: TODO
  • Source: git https://github.com/autonohm/ohm_tsd_slam.git (branch: indigo-devel)

Welcome to the ohm_tsd_slam ROS wiki page. Ohm_tsd_slam is the SLAM approach of the RoboCup Rescue Team Autonohm from the Technische Hochschule Nuremberg, Germany.

The release includes a SLAM package using 2D LIDAR data only as input. Its localization module uses ICP-based registration. The mapping uses a grid map, which cells contain Truncated Signed Distances (tsd), similar to the well known KinectFusion approach. This representation performs dynamic mapping, wherefore temporary objects are removed over time.

Simultaneously we are currently working on the release of two important features of our SLAM.

1. RANSAC-aided registration

  • This is more robust also it is slower than the ICP registration. This feature can already be tested by changing the parameter "registration_mode". You need to use lower ICP distance filter values for this!

2. Multi-robot SLAM

  • Multiple robots build one map simultaneously. This approach has the benefit that no map merging is necessary after the mission. This strategy has been deployed by Team Autonohm at the RoboCup German Open 2015.

The repository comes with an example launchfile, slam.launch. Its parameters are set to fit the typical RoboCup rescue scenario deploying a Hokuyo UTM30LX LIDAR or a sensor with similar parameters.

This video shows a demo of the package. It uses public available recorded Lidar data, acquired from the University of Freiburg (http://kaspar.informatik.uni-freiburg.de/~slamEvaluation/datasets.php).

The ohm_tsd_slam package is based on our CPU version of the well known KinectFusion approach, and is available at Researchgate.

S. May, P. Koch, R. Koch, C. Merkl, C. Pfitzner and A. Nuechter.
A Generalized 2D and 3D Multi-Sensor Data Integration Approach based on Signed Distance Functions for Multi-Modal Robotic Mapping.
In Proceedings of the VMV 2014: Vision, Modeling & Visualization, Darmstadt, Germany, 2014.

The multi-robot SLAM has been subject of a paper itself and can be downloaded at IEEEexplore.

P. Koch, S. May, M. Schmidpeter, M. Kühn, J. Martin, C. Pfitzner, C. Merkl, M. Fees, R. Koch and A. Nüchter.
Multi-Robot Localization and Mapping based on Signed Distance Functions.
In Proceedings of the IEEE International Conference on Autonomous Robot Systems and Competitions (ICARSC '15), Vila Real, Portugal, April 2015.

This video shows an experiment performed for the mentioned publication. Both robots of our rescue robot team perform cooperating SLAM of a building floor:

Basic Installation

The algorithms used for ohm_tsd_slam are distributed with the obviously library. After checking out the catkin package you can use wstools and rosdep to install obviously within in the SLAM.

If you like to install obviously externally it is recommended to use the master branch and follow the installation instructions provided in the GitHub repository of obviously library.

The basic installation to use obviously only for the ohm_tsd_slam is explained here:

Clone the catkin package in your desired catkin workspace with.

$ #In your catkin workspace
$ cd src
$ git clone https://github.com/autonohm/ohm_tsd_slam
$ cd ohm_tsd_slam
$ git checkout indigo-devel
$ cd ../..

Clone the obviously library. It contains the algorithms used by the SLAM

$ wstool update -t src/ohm_tsd_slam

If you never used rosdep, run these two commands first. Otherwise you can skip them.

$ sudo rosdep init
$ rosdep update

Source your workspace and run rosdep to install the necessary system dependencies. You maybe need sudo to install necessary dependencies.

$ source devel/setup.bash #for example
$ rosdep install ohm_tsd_slam

Now, building the package should be no problem. Just run catkin_make. For example:

$ catkin_make --only-pkg-with-deps ohm_tsd_slam

Finally, you can use the slam.launch launchfile to run the SLAM. If you play a bagfile that publishes sensor_msgs::LaserScan on the "/scan" topic you will receive a map on topic "/map" and the robot's pose on "/pose"

$ roslaunch ohm_tsd_slam slam.launch

ROS Nodes

slam_node

SLAM node for single robot SLAM and multi robot SLAM.

Published Topics

map (nav_msgs/OccupancyGrid)
  • Map of the environment
pose (geometry_msgs/PoseStamped)
  • Absolute robot pose in the map frame.

Parameters

map_size (integer, default: 10)
  • Quadratic size of the map with a side length of 2map_size * cell_size. E. g. map_size = 10, cell_size = 0.01 m -> side length = 210 * 0.01 m = 10.24 m
cell_size (double, default: 0.025)
  • Size of a cell in meters. It influences the absolute map size
x_offset (double, default: 0.5)
  • Origin offset on the X-axis from lower left corner of the map. In meters.
y_offset (double, default: 0.5)
  • Origin offset on the Y-axis from lower left corner of the map. In meters.
yaw_offset (double, default: 0.0)
  • Orientation offset of the origin to the place the SLAM was initialized (rotation around vertical Z-axis)
min_range (double, default: 0.001)
  • Minimal range of the raycaster in meters. Set this to the attributes of the used laser scanner.
max_range (double, default: 30.0)
  • Maximal range of the raycaster in meters. Set this to the attributes of the used laser scanner.
low_reflectivity_range (double, default: 2.0)
  • Something which helps against glass reflections.. To be done
occ_grid_time_interval (double, default: 2.0)
  • The time [s] that needs to pass before an update of the map is published again
loop_rate (double, default: 40.0)
  • Node frequency of the SLAM in Hz. This has no influence on the map or pose frequency.
pose_topic (string, default: pose)
  • Topic for pose updates
tf_base_frame (string, default: /map)
  • Map coordinate system
tf_child_frame (string, default: /laser)
  • Robot or Laser coordinate system
truncation_radius (double, default: 3.0)
  • Number of cells used for the truncated signed distance function. Simply interpretable as the thickness of the walls, just more complex. Please, see xyz for further details.
map_topic (string)
  • Topic for map publisher
get_map_topic (string)
  • Advertise a service that returns a map as nav_msgs/OccupancyGrid with this name.
footprint_width (double, default: 0.5)
  • Width of the robot (y-axis). This space is cleared when the map is initialized.
footprint_height (double, default: 0.5)
  • Height of the robot (x-axis). This space is cleared when the map is initialized.
footprint_x_offset (double, default: 0.28)
  • The described rectangle is described around the laser scanner. Move it correctly that it fits to the robot's size.
registration_mode (int, default: 0)
  • Desired registration algorithm. 0 = ICP Registration with distance filter. 1 = Experimental mode with RANSAC aided ICP. Option 1 is slower but more robust than ICP only registration.
dist_filter_max (double, default: 2.0)
  • The maximum distance for point matches. This is a cascading distance filter with every iteration the maximum value is reduced until it reaches the minimum value dist_filter_min.
dist_filter_min (double, default: 0.1)
  • The minimum distance for point matches.
icp_iterations (int, default: 25)
  • Number of ICP iterations for scan matching
reg_trs_max (double, default: 0.25)
  • Maximum translation allowed between two matched scans
reg_sin_rot_max (double, default: 0.17)
  • Maximal allowed rotation between two matched scans
node_control_topic (double, default: node_control)
  • Name of the node_control service to start stop and reset the SLAM
ransac_trials (int, default: 50)
  • Number of RANSAC iterations. Needs to be high for a big number of outliers.
ransac_eps_tresh (double, default: 0.15)
  • Threshold for outlier rejection in meters
ransac_ctrlset_size (int, default: 180)
  • Number of points in the control set to rate a estimated transformation between to laser scans
ransac_phi_max (double, default: 45)
  • Maximum expected rotational offset between two laser scans in degrees

Wiki: ohm_tsd_slam (last edited 2015-11-30 17:21:10 by MarkusKuehn)