Wiki

Package Summary

gmcl, which stands for general monte carlo localization, is a probabilistic-based localization technique for mobile robots in 2D-known map. It integrates the adaptive monte carlo localization - amcl - approach with three different particle filter algorithms (Optimal, Intelligent, Self-adaptive) to improve the performance while working in real time.

Main node structure and amcl-algorithms’s code was derived, with thanks, from Brian Gerkey's amcl package.

  • Maintainer status: developed
  • Maintainer: Mhd Ali Alshikh Khalil <adler1994 AT gmail DOT com>
  • Author: Mhd Ali Alshikh Khalil, adler1994@gmail.com
  • License: LGPL
  • Source: git https://github.com/adler-1994/gmcl.git (branch: master)

Citation Note

If you are using this package in your research work, please cite our article, more infohere.

Installation

Before installing gmcl package, please install ROS navigation stack in your ROS workspace. You can do that with the following command:

$ sudo apt-get install ros-$ROS_DISTRO-navigation

Then download gmcl package and place it inside the /src folder of your catkin workspace and compile it, which can be done through following commands:

$ cd catkin_ws
$ git clone -b master https://github.com/adler-1994/gmcl src/gmcl
$ catkin_make

Following video shows gmcl in comparison to amcl while running on the famous turtlebot 3 inside Gazebo simulation in solving the 3 localization problems (Pose Tracking, Global Localization, Kidnapped-robot):

Algorithms

Algorithms could be divided into new and migrated from amcl:

Migrated From amcl

Many of the algorithms and their parameters are well-described in the book Probabilistic Robotics, by Thrun, Burgard, and Fox. The user is advised to check there for more detail. In particular, we use the following algorithms from that book: sample_motion_model_odometry, beam_range_finder_model, likelihood_field_range_finder_model, Augmented_MCL, and KLD_Sampling_MCL.

New Algorithms

Besides algorithms implemented in amcl, gmcl takes advantage of Optimal particle filter as described here and  Intelligent particle filter as described here and Self-adaptive particle filter as described here to improve the performance of amcl while working in real time.

Modifications done on new algorithms to integrate them with amcl, Pseudo code of amcl & gmcl algorithms, performance and complexity analysis of amcl & gmcl are well-described in article here.

Package Requirements

In order to localize a mobile robot inside a map using gmcl package, following must be represented:

Complete TF Tree

The robot state publisher node – more info here– must be running with ~robot_description param of the robot’s urdf and publishes the tf of robots links (base link and lasers links). In addition, a motion controller should publish the estimated robot motion as a transform between the odometry frame (~odom_frame_id) and the base frame (~base_frame_id).

Occupancy Grid Map

A map server node –more info here– must publish a valid map using correct YAML format.

Laser Scans

Robot must be equipped with at least one laser scanner. All lasers must be fixed in place with respect to the robot base because gmcl looks up the transform between the laser's frame (~laser_frame_id) and the base frame (~base_frame_id), and latches it forever. So gmcl ”cannot” handle a laser that moves with respect to the base. All lasers should publish their scans as (sensor_msgs/LaserScan) massege.

Examples

Example of launch file that runs gmcl node and its parameters on Differential drive mobile robot

../gmcl/examples/gmcl_diff.launch 

To run gmcl node with initial estimated pose e.g. at (x, y, yaw) := (-1, 2, 0.6)

$ rosrun gmcl gmcl_diff.launch initial_pose_x:=-1 initial_pose_y:=2 initial_pose_a:=0.6

Example of launch file that runs gmcl node and its parameters on Holonomic wheeled mobile robot

../gmcl/examples/gmcl_omni.launch

To run gmcl node with initial estimated pose e.g. at (x, y, yaw) := (-1, 2, 0.6)

$ rosrun gmcl gmcl_omni.launch initial_pose_x:=-1 initial_pose_y:=2 initial_pose_a:=0.6

gmcl Node

Just like amcl, gmcl takes in a laser-based map, laser scans, and transform messages, and outputs pose estimates. On startup, gmcl 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). The drawing below shows localization using gmcl. During operation gmcl estimates the transformation of the base frame (~base_frame_id) in respect to the map frame (~global_frame_id) but it only publishes the transform between map frame and the odometry frame (~odom_frame_id). Essentially, this transform accounts for the drift that occurs using Dead Reckoning. gmcl_localization.png

Subscribed Topics

scan (sensor_msgs/LaserScan)

tf (tf/tfMessage)

initialpose (geometry_msgs/PoseWithCovarianceStamped)

map (nav_msgs/OccupancyGrid)

Published Topics

gmcl_pose (geometry_msgs/PoseWithCovarianceStamped)

gmcl_particlecloud (geometry_msgs/PoseArray)

gmcl_SER (geometry_msgs/PoseArray)

tf (tf/tfMessage)

Services

global_localization (std_srvs/Empty)

request_nomotion_update (std_srvs/Empty)

set_map (nav_msgs/SetMap)

Services Called

static_map (nav_msgs/GetMap)

Parameters

Besides Parameters that amcl uses to configure its node –Please check them– , gmcl adds eleven Parameters to overall filter parameters to configure the gmcl node and they are:

~use_optimal_filter (bool, default: false (disabled))

~use_intelligent_filter (bool, default: false (disabled))

~use_self_adaptive (bool, default: false (disabled))

~use_kld_sampling (bool, default: true)

Previous parameters define the Flow of gmcl algorithm and can be seen in following drawing….. flow_chart.png Full size available here.

The following table shows name of different techniques based on filters implemented, it could be seen that gmcl works with default parameters same as amcl….. table.png

~N_aux_particles (int, default: 10)

Real Time Caution

Be careful when setting the number of auxiliary particles, since they increase linearly the time required to calculate the new pose and weight of filter’s particles…..more details in article.

~crossover_alpha (double, default: 0.5)

~mutation_probability (double, default: 0.1)

~energy_map_resolution_x (double, default: 0.2 meters)

~energy_map_resolution_y (double, default: 0.2 meters)

Carsh Warning

Don’t set either of energy_map_resoluation_x or -resoultion_y to zero or gmcl node won’t execute.

~energy_threshold_value (double, default: 0.05)

~publish_ser (bool, default: false)

Feedback

To report a bug, or suggest an enhancement, please create a Github issue here.

If you already have enhanced the code and want to add your changes to the main code, please send a Github pull request through your forked copy of gmcl repository for merging. If you are not familiar with pull requests please visit page.

If you have a question, please post it on ROS answers, make sure your question is tagged by gmcl so I get notified.

Acknowledgements & Citation

This package was written during my master's thesis at Tishreen University, Syria. My thesis advisor is Dr.Iyad Hatem. iyad-mhd.png

This work has been published as an article here. To properly cite it, please use the following:

@article{article,
author = {Alshikh Khalil, Mhd Ali and Hatem, Iyad},
issue = {Vol. 43 No. 6 (2021)},
pages = {119-137},
title = {Development of a New Technique in ROS for Mobile Robots Localization in Known-Based 2D Environments},
journal = {Tishreen University Journal of Research and Scientific Studies - Engineering Sciences Series}}

Wiki: gmcl (last edited 2022-05-23 18:21:25 by MHD ALI ALSHIKH KHALIL)