[ros-users] [Discourse.ros.org] [General] Announcing the 'laser_odometry' package

Jeremie ros.discourse at gmail.com
Mon Sep 25 11:20:42 UTC 2017



Dear ROS user,

please let me introduce the [laser_odometry](https://github.com/artivis/laser_odometry) package.

This `pluginlib`-based ROS package aims at providing a unified API for laser scan matcher in the context of laser odometry.
While there are nowadays several publicly available scan matcher ([csm](https://github.com/AndreaCensi/csm), [psm](https://github.com/ccny-ros-pkg/scan_tools/tree/indigo/polar_scan_matcher), [rf2o](https://github.com/MAPIRlab/rf2o_laser_odometry) to name a few), each and everyone of them uses it own internal data representation and API making it difficult to switch from one to another within a larger project for switching/testing/comparison purpose. This package aims at answering this difficulty.
By providing an abstract base class it allows one to declare a unique scan matcher object in a project leveraging the benefit of a unified API, while the `laser_odometry_node` is a stand alone ROS node which laser scan matcher type is selected at launch time by an argument (the plugin type) and publishes the estimated pose either as a `geometry_msgs::Pose2D` or a `nav_msgs::Odometry`.

<p align="center">
  <img width="344" height="166" src='/uploads/ros/original/2X/5/5c1fc7297fd5c1bf7336b4b9927d2ad6707eb866.gif'>
</p>

The plugins already implemented are :

* [laser_odometry_csm](https://github.com/artivis/laser_odometry_csm)
* [laser_odometry_polar](https://github.com/artivis/laser_odometry_polar)
* [laser_odometry_rf2o](https://github.com/artivis/laser_odometry_rf2o)
* [laser_odometry_libpointmatcher](https://github.com/artivis/laser_odometry_libpointmatcher)

Please notice that as of today this is still an ongoing development thus the API is **not** completely stable and is likely to evolve with more extensive use of the package, feedback etc ... However the project seems mature enough for other people to test it and possibly join the effort.
Please also notice that releases were made of a very early version of the package, thus are outdated. New ones are planned as soon as the project seems stable.

While hopping that some of you will find this project useful, I am definitely looking forward for comments and feedback !

Thanks.

Jeremie Deray.

----------
Notes : 

The `laser_odometry_core` package provides a base-class from which is derived plugins wrapping scan matchers. The base-class implements most of the scan matcher common operations (e.g. frames and covariances composition) reducing the work of the derived plugin to overloading a single function that computes the scan alignment. While enforcing the API, the base class is also flexible in its workflow by offering the possibility to overload several functions along the sequential execution of the overall scan matching (e.g. `initialization`, `preProcessing`, see the [overall pseudo-code](https://github.com/artivis/laser_odometry/wiki/Overall-execution-pseudo-code)). Find more details on the [wiki page dedicated to plugin creation](https://github.com/artivis/laser_odometry/wiki/Create-a-plugin).

The package aims at handling laser odometry, thus either 2D or 3D. While the 2D case has concentrated most of the effort so far, the API already handles `sensor_msgs::PointCloud2` and hopefully the 3D case will be handled soon thanks to the [laser_odometry_libpointmatcher](https://github.com/artivis/laser_odometry_libpointmatcher) plugin.





---
[Visit Topic](https://discourse.ros.org/t/announcing-the-laser-odometry-package/2745/1) or reply to this email to respond.




More information about the ros-users mailing list