Skip to content

li9i/fsm-lo

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

68 Commits
 
 
 
 
 
 
 
 
 
 

Repository files navigation

FSM: Correspondenceless scan-matching of panoramic 2D range scans

ieeexplore.ieee.org youtube.com github.com

fsm_lo is a ROS package written in C++ that provides LIDAR odometry from measurements of a single panoramic 2D LIDAR sensor, that is: a sensor whose field of view is 360 degrees. fsm_lo is the ROS wrapper of fsm.

Lidar odometry is achieved via scan-matching but without establishing correspondences between elements of the input scans or their properties, but by leveraging the range signal's periodicity. Hence FSM may exploit properties of the Discrete Fourier Transform, which it does. These two pillars support the robustness of FSM's pose error against (a) sensor noise and (b) distance between consecutive poses, as you can see in the figure that summarises key experiments below.

Why use FSM

Experimental results at a glance

Table of Contents

Pre-installation

fsm-lo 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 then see the INSTALLATION_DEPRECATED.md guide.

Installation

Build the image with the most recent code of this repository using compose with

git clone git@github.com:li9i/fsm-lo.git
cd fsm-lo
docker compose build

or pull the docker image and run it with

docker pull li9i/fsm-lo:latest

docker run -it \
    --name=fsm_lo_container \
    --env="DISPLAY=$DISPLAY" \
    --net=host \
    --rm \
    li9i/fsm-lo:latest

Run

Launch

docker compose up

Call

Launching fsm simply makes it go into stand-by mode and does not actually execute anything. To do so simply call the provided service

docker exec -it fsm_lo_container sh -c "source ~/catkin_ws/devel/setup.bash; rosservice call /fsm_lo/start"

Nodes

fsm_lo_node

Subscribed topics

Topic Type Utility
scan_topic sensor_msgs/LaserScan 2d panoramic scans are published here
initial_pose_topic geometry_msgs/PoseWithCovarianceStamped optional---for setting the very first pose estimate to something other than the origin

Published topics

Topic Type Utility
pose_estimate_topic geometry_msgs/PoseStamped the current pose estimate relative to the global frame is published here
path_estimate_topic nav_msgs/Path the total estimated trajectory relative to the global frame is published here
lo_topic nav_msgs/Odometry the odometry is published here

Services offered

Service Type Utility
fsm_lo/clear_estimated_trajectory std_srvs/Empty clears the vector of estimated poses
fsm_lo/set_initial_pose std_srvs/Empty calling this service means: node subscribes to initial_pose_topic, obtains the latest pose estimate, sets fsm's initial pose, and unsubscribes
fsm_lo/start std_srvs/Empty commences node functionality
fsm_lo/stop std_srvs/Empty halts node functionality (node remains alive)

Parameters

Found in config/params.yaml:

IO Topics Description
scan_topic 2d panoramic scans are published here
initial_pose_topic (optional) the topic where an initial pose estimate may be provided
pose_estimate_topic fsm_lo's pose estimates are published here
path_estimate_topic fsm_lo's total trajectory estimate is published here
lo_topic fsm_lo's odometry estimate is published here
Frame ids Description
global_frame_id the global frame id (e.g. /map)
base_frame_id the lidar sensor's reference frame id (e.g. /base_laser_link)
lo_frame_id the (lidar) odometry's frame id
FSM-specific parameters Description Default value
size_scan the size of scans that are matched (execution time is proportional to scan size, hence subsampling may be needed) 360
min_magnification_size base angular oversampling 0
max_magnification_size maximum angular oversampling 3
num_iterations Greater sensor velocity requires higher values 2
xy_bound Axis-wise radius for randomly generating a new initial position estimate in case of recovery 0.2
t_bound Angular-wise radius for randomly generating a new initial orientation estimate in case of recovery π/4
max_counter Lower values decrease execution time 200
max_recoveries Ditto 10

Transforms published

lo_frame_id <- base_frame_id

in other words fsm_lo_node publishes the transform from /base_laser_link (or equivalent) to the equivalent of /odom (in this case lo_frame_id)

Motivation and Under the hood

1 min summary video

IMAGE ALT TEXT

IROS 2022 paper

@INPROCEEDINGS{9981228,
  author={Filotheou, Alexandros and Sergiadis, Georgios D. and Dimitriou, Antonis G.},
  booktitle={2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  title={FSM: Correspondenceless scan-matching of panoramic 2D range scans},
  year={2022},
  pages={6968-6975},
  doi={10.1109/IROS47612.2022.9981228}}