Only released in EOL distros:  

Package Summary

Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry. For full description of the algorithm, please refer to: Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016 Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217

  • Maintainer status: maintained
  • Maintainer: Javier G. Monroy <jgmonroy AT uma DOT es>
  • Author: Mariano Jaimez <marianojt AT uma DOT es>, Javier G. Monroy <jgmonroy AT uma DOT es>
  • License: GPL v3
  • Source: git https://github.com/MAPIRlab/mapir-ros-pkgs.git (branch: master)

Algorithm

RF2O is a fast and precise method to estimate the planar motion of a lidar from consecutive range scans. For every scanned point we formulate the range flow constraint equation in terms of the sensor velocity, and minimize a robust function of the resulting geometric constraints to obtain the motion estimate. Conversely to traditional approaches, this method does not search for correspondences but performs dense scan alignment based on the scan gradients, in the fashion of dense 3D visual odometry. The minimization problem is solved in a coarse-to-fine scheme to cope with large displacements, and a smooth filter based on the covariance of the estimate is employed to handle uncertainty in unconstraint scenarios (e.g. corridors).

The user is advised to check the related papers (see here) for a more detailed description of the method.

Demo Video

Nodes

rf2o_laser_odometry

The rf2o_laser_odometry node publishes planar odometry estimations for a mobile robot from scan lasers of an onboard 2D lidar. It initially estimates the odometry of the lidar device, and then calculates the robot base odometry by using tf transforms.

Subscribed Topics

laser_scan (sensor_msgs/LaserScan)
  • Laser scans to process. (This topic can be remapped via the ~laser_scan_topic parameter)
tf (tf/tfMessage)
  • Transforms

Published Topics

odom (nav_msgs/Odometry)
  • Odometry estimations as a ROS topic. (This topic can be remapped via the ~odom_frame_id parameter)
tf (tf/tfMessage)
  • Publishes the transform from the \base_link (which can be remapped via the ~base_frame_id parameter) to \odom (which can be remapped via the ~odom_frame_id parameter).

Parameters

~laser_scan_topic (string, default: /laser_scan)
  • Topic name where lidar scans are being published.
~base_frame_id (string, default: /base_link)
  • TF frame name of the mobile robot base. A tf transform from the laser_frame to the base_frame should exist.
~odom_frame_id (string, default: /odom)
  • TF frame name for published odometry estimations. This same parameter is used to publish odometry as a topic.
~freq (double, default: 10.0)
  • Odometry publication rate (Hz).

Wiki: rf2o (last edited 2016-04-14 10:22:18 by JavierGMonroy)