cbgl
is a ROS package written in C++ that allows you to localise your 2D LIDAR sensor in a given 2D occupancy grid map under global uncertainty in position and orientation, in minimal time
-
You can expect the execution time to roughly have an order of magnitude of
$10e \cdot \text{area} \cdot N_s$ microseconds, where$\text{area}$ is the area of the map's free space and$N_s$ is the LIDAR's number of rays. (Strictly speaking the execution time varies according to the geometry of the environment and other factors.) In the video below the environment area is$2000$ m$^2$ and localisation is performed in under four seconds -
CBGL does not require motion for performing global localisation: it's a one-shot approach that only requires a single laser scan measurement and the map of the sensor's environment
cbgl_in_willowgarage.mp4
A panoramic 2D LIDAR sensor mounted on a turtlebot 2 is spawned into
an environment at a pose whose immediate surroundings are repeated in (almost)
the same geometry and proportions at locations other than the sensor's spawning
ground. The user calls the global localisation service once before moving the
robot at a second challenging pose, at which she calls it for a second time.
Both times cbgl
is successful in estimating the sensor's pose. Sensor
characteristics:
cbgl
is installed, launched, and called via Docker:
- if this is your first time running docker then I happen to find this docker installation guide very friendly and easy to follow
- if instead you wish to install and run the package natively in Ubuntu 16.04, see the INSTALLATION_DEPRECATED.md guide.
Build the image with the most recent code of this repository with:
git clone [email protected]:li9i/cbgl.git
cd cbgl
docker compose build
or pull it:
docker pull li9i/cbgl:latest
If you cloned the repository then you may run the image via compose
cd cbgl
docker compose up
or, in any case, you may run the image with
docker run -it \
--name=container_cbgl \
--net=host \
--rm \
li9i/cbgl:latest
Launching cbgl
simply makes it go into stand-by mode and does not actually localise your sensor. To do so simply call the provided service
docker exec -it cbgl_container sh -c "source ~/catkin_ws/devel/setup.bash; rosservice call global_localization"
- [in] A
sensor_msgs/LaserScan
message published through topicconfiguration_files/scan_topic
- [in] A
nav_msgs/OccupancyGrid
message published through topicconfiguration_files/map_topic
- [out] A
geometry_msgs/PoseWithCovarianceStamped
message published through topicconfiguration_files/output_pose_topic
- [out] The transform between the
odom
frame and themap
frame ifconfiguration_files/tf_broadcast
is set totrue
The theoretical underpinning, key aspects, and experimental performance of CBGL are presented in the 2024 IEEE/RSJ International Conference on Intelligent Robots and Systems article cited through
@INPROCEEDINGS{10802235,
author={Filotheou, Alexandros},
booktitle={2024 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
title={CBGL: Fast Monte Carlo Passive Global Localisation of 2D LIDAR Sensor},
year={2024},
pages={3268-3275},
doi={10.1109/IROS58592.2024.10802235}}