Github Source: https://github.com/or-tal-robotics/mcl_pi_gazebo

Algorithms

mcl_pi is a package for cooperative robots localization (or for a single robot). It is based on using a distributed fusion technique for particle filter named "Particles Intersection" [1]. This package contains two main classes: Monte Carlo Localization (MCL) implementation in python, based on [2], and a Particles Intersection (PI) algorithm based on [1].

This implementation works only with laser scans and occupancy-grid based maps. The PI algorithm can be extended to any type of recursive Bayesian estimators, in particular, particle filters.

Example

Nodes

mcl

mcl takes in an occupancy grid based map, laser scans, and odometry data, and outputs a numerical approximation of the posterior distribution. On startup, mcl initializes its particle filter according to the parameters provided. Note that, because of the defaults, if no parameters are set, the initial filter state will be a moderately sized particle cloud centered about (0,0,0).

Subscribed Topics

scan (sensor_msgs/LaserScan)
  • Laser scans.
initialpose (geometry_msgs/PoseWithCovarianceStamped)
  • Mean and covariance with which to (re-)initialize the particle filter.
map (nav_msgs/OccupancyGrid)
  • When the use_map_topic parameter is set, mcl subscribes to this topic to retrieve the map used for laser-based localization.
odom (nav_msgs/Odometry)
  • Odometry data (with covariance)

Published Topics

MCL_estimated_pose (geometry_msgs/PoseWithCovarianceStamped)
  • Robot's estimated pose in the map, with covariance.
particlecloud (geometry_msgs/PoseArray)
  • The set of pose estimates being maintained by the filter.
particlecloud2fuse_out (geometry_msgs/PoseArray)
  • A particle based estimation of the othere robots state. used for fusion.
laser_frame (tf/tfMessage)
  • Publishes the transform from odom (which can be remapped via the ~odom_frame_id parameter) to map.

mcl_pi

mcl_pi uses the mcl node to run a self-localization algorithm on a single robot. Besides that, it searches robots in a view area when a robot found it subscribes to his particlecloud2fuse_out topic and uses it to enhance its localization.

Subscribed Topics

scan (sensor_msgs/LaserScan)
  • Laser scans.
initialpose (geometry_msgs/PoseWithCovarianceStamped)
  • Mean and covariance with which to (re-)initialize the particle filter.
map (nav_msgs/OccupancyGrid)
  • When the use_map_topic parameter is set, mcl subscribes to this topic to retrieve the map used for laser-based localization.
odom (nav_msgs/Odometry)
  • Odometry data (with covariance)

Published Topics

MCL_estimated_pose (geometry_msgs/PoseWithCovarianceStamped)
  • Robot's estimated pose in the map, with covariance.
particlecloud (geometry_msgs/PoseArray)
  • The set of pose estimates being maintained by the filter.
transformed_particles (geometry_msgs/PoseArray)
  • A particle based estimation of the othere robots state. used for fusion.
laser_frame (tf/tfMessage)
  • Publishes the transform from odom (which can be remapped via the ~odom_frame_id parameter) to map.
estimated_pose (geometry_msgs/PointStamped)
  • Robot's estimated pose in the map as point)
other_robot_observation (sensor_msgs/PointCloud)
  • A filtered observations of othere robots (Using a EKF)
scope (geometry_msgs/PolygonStamped)
  • A scope of the EKF estimation area

References

[1] Thrun S, Burgard W, Fox D. Probabilistic robotics. MIT press; 2005 Aug 19.

[2] Tslil, Or, and Avishy Carmi. "Information fusion using particles intersection." 2018 IEEE International Conference on Acoustics, Speech and Signal Processing (ICASSP). IEEE, 2018.

[3] Tslil, Or, Feiner Tal, and Avishy Carmi. "Distributed Information Fusion in Tangle Networks", Under review

Wiki: mcl_pi (last edited 2020-09-07 11:27:37 by Or Tslil)