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)
  • If parameter ~subscribe_scan is true, the topic on which laser scans (2D) are received.
/cloud_in (sensor_msgs/PointCloud2)
  • If parameter ~subscribe_cloud is true, the topic on which point clouds (2D or 3D) are received.

Published Topics

/point_map (sensor_msgs/PointCloud2)
  • Resulting map (2D or 3D depending on incoming data)
/icp_odom (nav_msgs/Odometry)
  • sensor to map frame odometry message
/icp_error_odom (nav_msgs/Odometry)
  • odom to map frame odometry message

Services

dynamic_point_map (map_msgs/GetPointMap)
  • Return the built map
~save_map (map_msgs/SaveMap)
  • Save the built map to the disk
~load_map (ethzasl_icp_mapper/LoadMap)
  • Load a map from the disk, reset odom-to-map transform to identity
~reset (std_srvs/Empty)
  • Clear the map and reset odom-to-map transform to identity
~correct_pose (ethzasl_icp_mapper/CorrectPose)
  • Set the odom-to-map transform
~set_mode (ethzasl_icp_mapper/SetMode)
  • Set the localizing/mapping mode
~get_mode (ethzasl_icp_mapper/GetMode)
  • Get the current localizing/mapping mode

Required tf Transforms

sensor frame/odom
  • sensor to odom frame transform, input from odometry

Provided tf Transforms

/odom/map
  • odom to map frame transform, result of ICP

Parameters

~icpConfig (string, no default)

  • Name of the YAML file configuring the modular ICP chain, see Configuration section.

~useROSLogger (bool, default: false)

  • If true, use ROS console for logging, otherwise use logger defined in config file.

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

  • The node listens to the topic whose name is defined by this parameter and expects a sensor_msgs/PointCloud2.

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

  • Topic on which to send delta pose.

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

  • Frame name used as fixed frame in the tf published by the node.

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

  • Frame name used as moving frame in the tf published by the node.

~startupDropCount (unsigned, default: 0)

  • Number of clouds to drop on startup, useful if sensor is producing garbage in a startup phase.

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)

  • This service takes two sensor_msgs/PointCloud2 messages as inputs (the first is the reference and the second the reading) and provides a geometry_msgs/Transform message as output. The resulting transformation can be used to move the reading point cloud.

Parameters

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

~config (string, no default)

~useROSLogger (bool, default: false)

  • If true, use ROS console for logging, otherwise use logger defined in config file.

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)