[Documentation] [TitleIndex] [WordIndex

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

2. Multi-robot SLAM

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) pose (geometry_msgs/PoseStamped)

Parameters

map_size (integer, default: 10) cell_size (double, default: 0.025) x_offset (double, default: 0.5) y_offset (double, default: 0.5) yaw_offset (double, default: 0.0) min_range (double, default: 0.001) max_range (double, default: 30.0) low_reflectivity_range (double, default: 2.0) occ_grid_time_interval (double, default: 2.0) loop_rate (double, default: 40.0) pose_topic (string, default: pose) tf_base_frame (string, default: /map) tf_child_frame (string, default: /laser) truncation_radius (double, default: 3.0) map_topic (string) get_map_topic (string) footprint_width (double, default: 0.5) footprint_height (double, default: 0.5) footprint_x_offset (double, default: 0.28) registration_mode (int, default: 0) dist_filter_max (double, default: 2.0) dist_filter_min (double, default: 0.1) icp_iterations (int, default: 25) reg_trs_max (double, default: 0.25) reg_sin_rot_max (double, default: 0.17) node_control_topic (double, default: node_control) ransac_trials (int, default: 50) ransac_eps_tresh (double, default: 0.15) ransac_ctrlset_size (int, default: 180) ransac_phi_max (double, default: 45)


2019-11-16 13:05