Skip to main content

Direct, modular georeferencing and drift-correction of point cloud maps

Project description

FlexCloud

Georeferencing of Point Cloud Maps

Linux Docker C++ License arXiv DOI:10.5220/0013405400003941

Installation

pip install flexcloud

Usage

All algorithm parameters are CLI flags with reasonable defaults.

Keyframe Interpolation

flexcloud-keyframe-interpolation [OPTIONS] <positions-path> <poses-path> [out-dir]

Required positional arguments:
  positions-path  Reference data (auto-detected, see table above)
  poses-path      SLAM trajectory in GLIM format
                  (one row per pose: stamp xpos ypos zpos xquat yquat zquat wquat)
  out-dir         Output directory for poses_keyframes.txt and positions_interpolated.txt
                  (defaults to the current directory)

Bag input (only used when positions-path is a ROS 2 bag):
  --pos-topic TEXT           Topic of NavSatFix or Odometry messages (required for bags)
  -t,--target-frame TEXT     TF frame to transform positions into (uses /tf and /tf_static
                             from the bag). Optional.
  --origin LAT LON ALT       Custom origin for NavSatFix → local Cartesian projection.
                             If omitted no projection is performed.

The reference-data source is given as a single positional argument positions-path; the reader is selected automatically:

positions-path is … Reader
a .txt file text-file reader (one position per line)
a directory without any .mcap / .db3 / .sqlite3 per-position txt-files reader
a .mcap / .db3 / .sqlite3 file, or a directory containing one ROS 2 bag reader

Reference-data file formats:

  • single .txt file — one position per line, whitespace-separated: stamp x y z x_stddev y_stddev z_stddev.
  • directory of per-position .txt files — filenames <sec>_<nanosec>.txt, file content x y z x_stddev y_stddev z_stddev (timestamp parsed from the filename).
  • ROS 2 bag — supports sensor_msgs/msg/NavSatFix or nav_msgs/msg/Odometry messages.

Notes on bag input:

  • NavSatFix messages are projected to local Cartesian via GeographicLib; standard deviations are taken from position_covariance (diagonal).
  • Odometry messages use pose.pose directly; standard deviations are taken from pose.covariance (diagonal).
  • When --target-frame is set, all /tf and /tf_static messages from the bag are pre-loaded into a TF buffer. For each message its transform to the target frame is looked using the message timestamp.

Examples:

# single txt file
flexcloud-keyframe-interpolation positions.txt poses_GLIM.txt

# ROS 2 bag with Odometry
flexcloud-keyframe-interpolation /path/to/bag.mcap poses_GLIM.txt /path/to/out \
    --pos-topic /odom --target-frame base_link

The keyframe-selection algorithm itself is unchanged:

  • keyframes are selected from the LiDAR trajectory based on minimum longitudinal distance (keyframe_delta_x) or minimum angular delta (keyframe_delta_angle).
  • For each LiDAR keyframe, the corresponding reference position is computed in one of two ways (controlled by interpolate):
    • Closest neighbor — pick the reference frame with the smallest timestamp delta.
    • Spline interpolation — fit a third-order spline through neighboring reference points (selected so that consecutive supports have a minimum euclidean distance of interp_pos_delta_xyz) and evaluate at the keyframe timestamp.
  • stddev_threshold is used to drop reference frames with high covariance.

The output is designed to be compatible with the georeferencing executable.

Georeferencing

flexcloud-georeferencing [OPTIONS] <positions-path> <poses-path>

Required positional arguments:
  positions-path        GNSS / reference trajectory (lat,lon,ele,*_stddev or
                        x,y,z,*_stddev if already cartesian)
  poses-path            SLAM trajectory in GLIM format

Inputs:
  --pcd PATH            Point cloud map to transform
  --config-file PATH    Optional YAML for index-based fine-tuning arrays

Trajectory matching:
  --control-points INT              (default: 10)
  --stddev-threshold FLOAT                 (default: 0.05)
  --square-size FLOAT FLOAT FLOAT          (default: 0.1 0.1 10.0)

Origin:
  --origin LAT LON ALT                     (default: empty)

All parameters are CLI flags with sensible defaults; the only YAML config that remains is for the index-based fine-tuning arrays (exclude_ind, shift_ind, shift_ind_dist, fake_ind, fake_ind_dist, fake_ind_height) and is supplied via --config-file.

Examples:

# defaults, cartesian reference, no point cloud
flexcloud-georeferencing positions_interpolated.txt poses_keyframes.txt

# supply index-based fine-tuning arrays via YAML
flexcloud-georeferencing reference.txt poses_keyframes.txt \
    --config-file config/georeferencing.yaml

Inspect results:

  • results of the rubber-sheet transformation & the resulting, transformed point cloud map are visualized in Rerun.
  • by default, the rerun viewer instance of the docker container is spawned. However, if you have problems with the viewer and your graphics drivers, you can also launch your viewer locally
  • adjust the parameters if the results are satisfying
  • see table for explanation of single topics
  • follow the instructions below (Content->Analysis) to get a quantitative evaluation fo the georeferencing
  • the results are automatically saved in the current working directory within the folder output/traj_matching/
  • Quick usage (the directory output/traj_matching is automatically generated at the current working directory):
python3 plot_traj_matching.py /path/to/output/traj_matching/
Type Description
Trajectory reference trajectory
Trajectory_SLAM original SLAM trajectory
Trajectory_align SLAM trajectory aligned to reference with Umeyama transformation
Trajectory_RS SLAM trajectory after rubber-sheet-transformation
control_points control points used for rubber-sheeting
tetrahedra triangulation used for rubber-sheeting
pcd_map transformed point cloud map
  • Inspect results and modify parameters if desired.

Content

This project enables the georeferencing of an existing point cloud map created only from inertial sensor data (e.g. LiDAR) by the use of the corresponding GNSS data. Leveraging the concept of rubber-sheeting from cartography, the tool is also able to account for accumulated errors during map creation and thus rectify the map.

image Detailed documentation of the modules can be found below.

Trajectory Matching

  • calculation of transformation based on GNSS/reference and SLAM trajectories
  • trajectories do not have to be time-synchronized, although time-synchronization is required to select control points automatically for rubber-sheeting

1. Projection of Global Coordinates

  • global coordinates may be projected into local coordinate system using ENU-coordinates from the GeographicLib

2. Keyframe Interpolation

- Selection of keyframes and interpolation of global position frames for map creation and manual optimization - Interpolation follows a third-order spline interpolation from [Eigen](https://eigen.tuxfamily.org/dox/unsupported/group__Splines__Module.html)

3. Alignment of Trajectories by Rigid Transformation

  • SLAM trajectory aligned to reference using Umeyama algorithm transformation in 2D/3D
  • application of calculated transformation on SLAM trajectory
  • screenshot below shows results of alignment of SLAM trajectory to projected reference trajectory with Umeyama algorithm
    image

4. Rubber-Sheet transformation

  • piecewise linear rubber-sheet transformation in 2D/3D based on concept of Griffin & White
  • using Delaunay triangulation from CGAL
  • manual selection of control points in RVIZ (see above) possible if trajectories are not time-synchronized (parameter auto_cp)
  • automatic exclusion of trajectory points as control points using thresholding for standard deviation possible
  • manual exclusion of indices as controlpoints and manual displacement in xy possible, see parameter descriptions
  • application of calculated transformations on target SLAM-poses and point cloud map
  • the two screenshots below show selected control points on the aligned trajectories from step 2 and the results of the rubber-sheet transformation
    image image

Evaluation

  • export of various data by setting corresponding parameters in config-file
    • data is exported to .txt files that are then read by python-scripts
    • set export path in config-file
    • adjust import paths at the beginning of python-scripts if necessary
  • analysis scripts in /analysis:
    • visualization of initial trajectories, Umeyama transformation and Rubber-Sheet transformation
    • execute script plot_traj_matching.py in /analysis
    • produces graphs shown in previous section
    • calculation of deviation between trajectories based on euclidean distance of points

Build from Source

git clone git@github.com:TUMFTM/FlexCloud.git
cd FlexCloud/
./docker/build_docker.sh  

You can also download built versions of the docker images from the github container registry. E.g. to download the latest container, run:

docker pull ghcr.io/tumftm/flexcloud:latest

Run the container and mount your data by appending the directory containing your data:

./docker/run_docker.sh /your/local/directory/data

Test Data

The data was recorded by the TUM Autonomous Motorsport Team during the Abu Dhabi Autonomous Racing League 2025. The LiDAR/SLAM trajectory is created using glim. The reference trajectory presents raw data from the RTK-corrected GNSS-signal of the vehicle.

Developers

  • Maximilian Leitenstern, Institute of Automotive Technology, School of Engineering and Design, Technical University of Munich, 85748 Garching, Germany
  • Marko Alten (student research project)
  • Christian Bolea-Schaser (student research project)

Citation

If you use this repository for any academic work, please consider citing our paper (preprint):

@misc{leitenstern2025flexcloud,
      title={FlexCloud: Direct, Modular Georeferencing and Drift-Correction of Point Cloud Maps}, 
      author={Maximilian Leitenstern and Marko Alten and Christian Bolea-Schaser and Dominik Kulmer and Marcel Weinmann and Markus Lienkamp},
      year={2025},
      eprint={2502.00395},
      archivePrefix={arXiv},
      primaryClass={cs.RO},
      url={https://arxiv.org/abs/2502.00395}, 
}

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distributions

No source distribution files available for this release.See tutorial on generating distribution archives.

Built Distribution

If you're not sure about the file name format, learn more about wheel file names.

flexcloud-1.0.0-cp312-cp312-manylinux_2_39_x86_64.whl (92.8 MB view details)

Uploaded CPython 3.12manylinux: glibc 2.39+ x86-64

File details

Details for the file flexcloud-1.0.0-cp312-cp312-manylinux_2_39_x86_64.whl.

File metadata

File hashes

Hashes for flexcloud-1.0.0-cp312-cp312-manylinux_2_39_x86_64.whl
Algorithm Hash digest
SHA256 ad2aaccc03711d1f0a1de215f5f2533125b37be7c48596bde2ea9c1753f5304b
MD5 12d63dd4ecb949df0c56660d57f740f2
BLAKE2b-256 61ea703a034cab6c7aa3d590dbea924cafd97ae83492c727a1810a74a4dfee47

See more details on using hashes here.

Provenance

The following attestation bundles were made for flexcloud-1.0.0-cp312-cp312-manylinux_2_39_x86_64.whl:

Publisher: pypi.yml on TUMFTM/FlexCloud

Attestations: Values shown here reflect the state when the release was signed and may no longer be current.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page