Wiki

Only released in EOL distros:  

ethzasl_icp_mapping: ethzasl_gridmap_2d | ethzasl_icp_mapper | ethzasl_icp_mapper_experiments | ethzasl_point_cloud_vtk_tools | libnabo | libpointmatcher | libpointmatcher_ros

Package Summary

2D/3D mapper based on libpointmatcher (http://github.com/ethz-asl/libpointmatcher)

Overview

One of the main problems with point-cloud registration solutions is that their efficiency often depends on the application. This package provides a convenient way to tune, test and deploy several registration solutions using the same node. It provides a real-time tracker and mapper in 2D and 3D, based on the libpointmachter and libnabo libraries. This allows a complete configuration of the registration chain through YAML files, see the chain configuration page for a list of modules and their parameters. You can think of this package as the front end of a SLAM system, including everything but loop-closure detection and relaxation.

For installation instructions, see the ethzasl_icp_mapping stack page. A preliminary version of this package was deployed in the ROS kinect contest.

Citing

Two papers talk about our open-source ICP library. The first one introduces the library and proposes a sound evaluation methodology using it. It was published in Autonomous Robots and can be found here (full text):

@ARTICLE{pomerleau13comparing,
   Author = {F. Pomerleau and F. Colas and R. Siegwart and S. Magnenat},
   Title = {Comparing ICP variants on real-world data sets},
   Journal = {Autonomous Robots},
   Volume = {34},
   Number = {3},
   Month = {April},
   Year = {2013},
   Pages = {133--148}
}

In addition, a paper using a preliminary version of this package to evaluate a Kinect tracker was presented at IROS 2011 and can be found here (fulltext):

@INPROCEEDINGS{pomerleau11tracking,
    author = {François Pomerleau and Stéphane Magnenat and Francis Colas and Ming Liu and Roland Siegwart},
    title = {Tracking a Depth Camera: Parameter Exploration for Fast ICP},
    booktitle = {Proc. of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
    publisher = {IEEE Press},
    pages = {3824--3829},
    year = {2011}
}

Quick Start

Since the proposed ICP chain is highly modular, it has many parameters. You can play with it directly if you have an openni-compatible sensor:

roscd ethzasl_icp_mapper 
roslaunch launch/openni/tracker_viewer.launch

You can then have a look into the launch/openni/ files to see how the openni tracker is configured. This file roughly corresponds to the following chain:

Sample ICP chain for openni

Starting from this chain, you can develop your own chain.

Nodes

mapper

This node performs continuous registration of point clouds and publishes the resulting pose using tf and through nav_msgs/Odometry messages. The type of topic messages must be sensor_msgs/LaserScan (2D) or sensor_msgs/PointCloud2 (2D or 3D). This effectively implements a real-time tracker in 2D or 3D.

Subscribed Topics

/scan (sensor_msgs/LaserScan) /cloud_in (sensor_msgs/PointCloud2)

Published Topics

/point_map (sensor_msgs/PointCloud2) /icp_odom (nav_msgs/Odometry) /icp_error_odom (nav_msgs/Odometry)

Services

dynamic_point_map (map_msgs/GetPointMap) ~save_map (map_msgs/SaveMap) ~load_map (ethzasl_icp_mapper/LoadMap) ~reset (std_srvs/Empty) ~correct_pose (ethzasl_icp_mapper/CorrectPose) ~set_mode (ethzasl_icp_mapper/SetMode) ~get_mode (ethzasl_icp_mapper/GetMode)

Required tf Transforms

sensor frame/odom

Provided tf Transforms

/odom/map

Parameters

~icpConfig (string, no default)

~useROSLogger (bool, default: false)

~cloudTopic (string, default: "/camera/rgb/points")

~deltaPoseTopic (string, default: "/openni_delta_pose")

~fixedFrame (string, default: "/world")

~sensorFrame (string, default: "/openni_rgb_optical_frame")

~startupDropCount (unsigned, default: 0)

Node: matcher_service

This node provides a service to match two point clouds.

Services offered

match_clouds (ethzasl_icp_mapper/MatchClouds.srv - custom messages in the package)

Parameters

As with the mapper node, the chain is configured through a YAML file.

~config (string, no default)

~useROSLogger (bool, default: false)

Node: occupancy_grid_builder

This node builds a 2D nav_msgs/OccupancyMap from sensor_msgs/LaserScan. It is yet to be fully documented.

Limitations

This library solely performs point-cloud registration, it does not incorporate data fusion based on IMU or odometry. This can be done through other nodes such as robot_pose_ekf.

Known bugs

The version released in ROS does not work in 2D, please use the latest git master version for this use case.

Report a Bug

Please report bugs and request features using the github page.

Wiki: ethzasl_icp_mapper (last edited 2013-12-19 13:59:16 by StephaneMagnenat)