fsm_lidom_ros
provides LIDAR odometry from measurements of a single panoramic 2D LIDAR sensor, a.k.a. a sensor whose field of view is 360 degrees. fsm_lidom_ros
is the ROS wrapper of fsm
.
Lidar odometry is achieved via scan-matching but without establishing correspondences by leveraging the range signal's periodicity. Hence FSM may exploit properties of the Discrete Fourier Transform. These two pillars support the robustness of FSM's pose error to sensor noise and distance between consecutive poses, as you can see in the figure that summarises key experiments below.
If this is your first time running docker then I happen to find this docker installation guide very friendly and easy to follow. Then build the image with the most recent code of this repository using compose
with
git clone git@github.com:li9i/fsm_lidom_ros.git
cd fsm_lidom_ros
docker compose build
or pull the docker image and run it with
docker pull li9i/fsm_lidom_ros:latest
docker run -it \
--name=fsm_lidom_ros_container \
--env="DISPLAY=$DISPLAY" \
--net=host \
--rm \
li9i/fsm_lidom_ros:latest
Tested in Ubuntu 16.04 and ROS kinetic
cd ~/catkin_ws/src
git clone git@github.com:li9i/fsm_lidom_ros.git
cd fsm_lidom_ros; mv fsm/* $PWD; rmdir fsm; cd ../..
catkin build fsm_lidom_ros
docker compose up
roslaunch fsm_lidom_ros avanti_fsm_lidom.launch
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_lidom_ros_container sh -c "source ~/catkin_ws/devel/setup.bash; rosservice call /fsm_lidom/start"
rosservice call /fsm_lidom/start
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 |
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 |
lidom_topic |
nav_msgs/Odometry |
the odometry is published here |
Service | Type | Utility |
---|---|---|
fsm_lidom/clear_estimated_trajectory |
std_srvs/Empty |
clears the vector of estimated poses |
fsm_lidom/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_lidom/start |
std_srvs/Empty |
commences node functionality |
fsm_lidom/stop |
std_srvs/Empty |
halts node functionality (node remains alive) |
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_lidom_ros 's pose estimates are published here |
path_estimate_topic |
fsm_lidom_ros 's total trajectory estimate is published here |
lidom_topic |
fsm_lidom_ros '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 ) |
lidom_frame_id |
the (lidar) odometry's frame id |
FSM-specific parameters | Description |
---|---|
size_scan |
the size of scans that are matched (execution time is proportional to scan size, hence subsampling may be needed) |
min_magnification_size |
base angular oversampling |
max_magnification_size |
maximum angular oversampling |
num_iterations |
Greater sensor velocity requires higher values |
xy_bound |
Axiswise radius for randomly generating a new initial position estimate in case of recovery |
t_bound |
Angularwise radius for randomly generating a new initial orientation estimate in case of recovery |
max_counter |
Lower values decrease execution time |
max_recoveries |
Ditto |
lidom_frame_id <- base_frame_id
in other words fsm_lidom_node
publishes the transform from /base_laser_link
(or equivalent) to the equivalent of /odom
(in this case lidom_frame_id
)
@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}}