Skip to content

Ultra-fast dense 2.5D elevation mapping engine for mobile robot navigation — CPU-only with ROS integration support

License

Notifications You must be signed in to change notification settings

Ikhyeon-Cho/FastDEM

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

72 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

FastDEM


Real-time elevation mapping on embedded CPUs — 100+ Hz on Jetson Orin

Quick Start · ROS1 · ROS2



Features

  • Fast — Real-time on embedded CPUs. Single thread, without GPU.
  • Lightweight — Minimal dependencies. No OpenCV, PCL, or Open3D.
  • Library-First — Clean C++ API, not a ROS node. Online (with TF) or offline (explicit transforms) support.
  • Sensor-Aware — Physics-based uncertainty models for LiDAR and RGB-D.
  • Multiple Estimators — Kalman Filter, Welford Mean, P² Quantile.
  • Local + Global Mapping — Robot-centric or map-centric modes.
  • Post-processing functions — Raycasting, Inpainting, Spike removal, Uncertainty fusion, etc.

How Fast?

The mapping itself runs at ~130 Hz — fast enough to leave ample headroom for post-processing.

Measured with Velodyne VLP-16 (~30K pts/scan) · 15×15 m map at 0.1 m resolution


Quick Start

1. Installation

Install dependencies

sudo apt install libeigen3-dev libyaml-cpp-dev libspdlog-dev

Clone and build

git clone https://github.com/Ikhyeon-Cho/FastDEM.git
cd FastDEM/fastdem
mkdir -p build && cd build
cmake .. -DCMAKE_BUILD_TYPE=Release
make -j$(nproc)

2. Standalone C++ Usage

Ideal for custom SLAM pipelines or non-ROS systems.

#include <fastdem/fastdem.hpp>

int main() {
    // 1. Setup map and mapper
    fastdem::ElevationMap map;
    map.setGeometry(15.0f, 15.0f, 0.1f);

    fastdem::FastDEM mapper(map);
    mapper.setHeightRange(-1.0f, 2.0f)
          .setDistanceRange(0.5f, 10.0f)
          .setEstimatorType(fastdem::EstimationType::Kalman)
          .setSensorModel(fastdem::SensorType::LiDAR);
    // -- or: FastDEM mapper(map, MappingConfig::load("config/default.yaml"));

    // 2. Integration Loop
    while (true) {
        // T_base_sensor: Sensor extrinsic (Sensor -> Robot)
        // T_world_base: Robot pose (Robot -> World)
        mapper.integrate(cloud, T_base_sensor, T_world_base);

        // Access the 2.5D elevation map
        float elevation = map.elevationAt(position);
    }
}

See fastdem/examples/ for more usage patterns.

3. Configuration

All default settings are in config/default.yaml.

4. Run with ROS

See ros1 and ros2 branches. These are just a thin ROS wrapper of core fastdem::FastDEM features.


Citation

FastDEM was originally developed for the following research:

'Learning Self-supervised Traversability with Navigation Experiences of Mobile Robots' IEEE Robotics and Automation Letters (RA-L), 2024

@article{cho2024learning,
  title={Learning Self-Supervised Traversability With Navigation Experiences of Mobile Robots: A Risk-Aware Self-Training Approach},
  author={Cho, Ikhyeon and Chung, Woojin},
  journal={IEEE Robotics and Automation Letters},
  year={2024},
  volume={9},
  number={5},
  pages={4122-4129},
  doi={10.1109/LRA.2024.3376148}
}

Report Bug · Pull Request

BSD-3-Clause License © Ikhyeon Cho

About

Ultra-fast dense 2.5D elevation mapping engine for mobile robot navigation — CPU-only with ROS integration support

Topics

Resources

License

Stars

Watchers

Forks