A high-performance 2D SLAM library for robot vacuum cleaners, featuring multi-sensor occupancy grid mapping, scan matching, and loop closure.
- Multi-Sensor Occupancy Grid: Semantic cell types (Floor, Wall, Cliff, Bump) with Bayesian probability updates
- Scan Matching: Correlative and branch-and-bound scan-to-map alignment with Gauss-Newton refinement
- Submap Architecture: Cartographer-inspired reversible map updates for loop closure correction
- Loop Closure: LiDAR-IRIS descriptors with pose graph optimization
- SIMD Optimized: Explicit
std::simdoperations withf32x4for portable SIMD (ARM NEON, x86 SSE/AVX) - SoA Data Layout: Structure-of-Arrays for cache-friendly, SIMD-efficient memory access
use vastu_slam::{OccupancyGridMap, MapConfig, Pose2D, LidarScan};
// Create map with default configuration (800Γ800 cells, 2.5cm resolution = 20mΓ20m)
let config = MapConfig::default();
let mut map = OccupancyGridMap::new(config);
// Process lidar scan
let pose = Pose2D::new(0.0, 0.0, 0.0);
let scan = LidarScan::new(ranges, angles, 0.15, 8.0);
let result = map.observe_lidar(&scan, pose);
println!("Updated {} cells", result.cells_updated);βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
β VastuSLAM Pipeline β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β β
β Sensors SLAM Core Output β
β βββββββ βββββββββ ββββββ β
β β
β βββββββββββ βββββββββββββββββββββββββββββββββββββββββββββββ βββββββββββ β
β β LiDAR ββββββΆβ Scan Matching ββββΆβ Pose β β
β β 360Β° β β ββββββββββββββββββββββββββββββββββββββββ β β Output β β
β βββββββββββ β β Coarse: Correlative / Branch-Bound β β βββββββββββ β
β β β Fine: Gauss-Newton + Distance Field β β β
β βββββββββββ β ββββββββββββββββββββββββββββββββββββββββ β βββββββββββ β
β β Cliff ββββββΆβ β ββββΆβ Map β β
β β Sensors β β βΌ β β .vastu β β
β βββββββββββ β ββββββββββββββββββββββββββββββββββββββββ β β .pgm β β
β β β Occupancy Grid β β βββββββββββ β
β βββββββββββ β β β’ Log-odds Bayesian updates β β β
β β Bumper ββββββΆβ β β’ Priority: Bump > Cliff > Wall β β βββββββββββ β
β β Sensors β β β β’ Bresenham ray casting β ββββΆβ Paths β β
β βββββββββββ β ββββββββββββββββββββββββββββββββββββββββ β β A* β β
β β β β βββββββββββ β
β βββββββββββ β βΌ β β
β β Encoder ββββββΆβ ββββββββββββββββββββββββββββββββββββββββ β β
β β Odom β β β Submap Manager β β β
β βββββββββββ β β β’ Local grid per submap β β β
β β β β’ Stored scans for regeneration β β β
β β β β’ Origin-only optimization β β β
β β ββββββββββββββββββββββββββββββββββββββββ β β
β β β β β
β β βΌ β β
β β ββββββββββββββββββββββββββββββββββββββββ β β
β β β Loop Closure β β β
β β β β’ LiDAR-IRIS descriptors β β β
β β β β’ Pose graph optimization β β β
β β β β’ Submap origin correction β β β
β β ββββββββββββββββββββββββββββββββββββββββ β β
β βββββββββββββββββββββββββββββββββββββββββββββββ β
β β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
VastuSLAM uses a Bayesian occupancy grid with log-odds representation for numerically stable probability updates:
Log-Odds Update:
L(cell | observation) = L(cell) + L(sensor_model)
Where:
β’ L_hit = +20 (observation confirms obstacle)
β’ L_miss = -4 (observation confirms free space)
β’ L_occupied_threshold = +50 β classify as Wall
β’ L_free_threshold = -50 β classify as Floor
The asymmetric weights (20 vs -4) mean a single hit strongly indicates an obstacle, while multiple passes are needed to clear a false positive.
Scan matching corrects encoder drift by aligning LiDAR scans to the existing map:
Pipeline:
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
β Step 1: COARSE SEARCH β
β β’ Window: Β±30cm Γ Β±30cm Γ Β±8.6Β° β
β β’ Resolution: 4cm linear, 2.3Β° angular β
β β’ Method: Brute-force or branch-and-bound β
β β’ Scoring: Gaussian distance field (smooth gradients) β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β Step 2: FINE SEARCH β
β β’ Window: Β±6cm Γ Β±6cm Γ Β±3.4Β° β
β β’ Resolution: 2cm linear, 1.1Β° angular β
β β’ Prior-penalized scoring β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β Step 3: GAUSS-NEWTON REFINEMENT β
β β’ Adaptive Levenberg-Marquardt β
β β’ Sub-millimeter accuracy β
β β’ Convergence: cost change < 1e-6 β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
Gaussian Scoring provides smooth gradients for optimization:
Score(point) = exp(-dΒ² / 2ΟΒ²)
Where d = distance to nearest wall, Ο = 0.10m (typical)
Inspired by Google Cartographer, VastuSLAM uses submaps for reversible map updates:
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
β World Frame β
β β
β Submap 0 Submap 1 Submap 2 β
β βββββββββββ βββββββββββ βββββββββββ β
β β Local β ββT01βββΆ β Local β ββT12βββΆ β Local β β
β β Grid β β Grid β β Grid β β
β β [scans] β β [scans] β β [scans] β β
β ββββββ¬βββββ ββββββ¬βββββ ββββββ¬βββββ β
β βΌ βΌ βΌ β
β origin_0 origin_1 origin_2 β
β (fixed) (adjustable) (adjustable) β
βββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββββ
Key Insight: Only submap origins change during optimization.
Local grids regenerate from stored scans.
Submap Lifecycle:
- Active: Receives scans, builds local grid
- Filling: Overlap period (scans go to both old and new submap)
- Finalized: No more updates, eligible for loop closure
Uses LiDAR-IRIS descriptors for efficient place recognition:
LiDAR-IRIS Pipeline:
1. Project scan β radial signature (range histogram by angle)
2. Extract features via Fourier transform
3. Create binary descriptor (rotation-invariant)
4. Compare using Hamming distance (fast bit operations)
5. Geometric validation with scan matching
6. Pose graph optimization if validated
Multiple sensors update the same cells. Priority ensures correct classification:
Priority (highest to lowest):
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ
β 4. Bump (invisible obstacle - glass, chair legs) β β Bumper sensor
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β 3. Cliff (floor drop-off - stairs, ledges) β β Cliff sensor
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β 2. Wall (visible obstacle) β β LiDAR endpoint
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β 1. Floor (traversable) β β LiDAR ray
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ€
β 0. Unknown (not observed) β β Initial state
βββββββββββββββββββββββββββββββββββββββββββββββββββββββ
| Module | Description | Documentation |
|---|---|---|
core |
Fundamental types: Pose2D, WorldPoint, GridCoord, LidarScan, Cell | README |
grid |
Occupancy grid storage with SoA layout, ray casting, sensor updates | README |
matching |
Scan matching (correlative, branch-bound), loop closure, pose graph | README |
submap |
Submap manager, pose graph, multi-submap matching | README |
config |
YAML configuration loading with sensible defaults | README |
io |
Persistence: native .vastu format, ROS .pgm export, SVG visualization | README |
modes |
Operation modes: localization-only (no map updates) | README |
evaluation |
Cartographer-style evaluation: ATE, RPE, pose relations metrics | README |
All coordinates follow the ROS REP-103 convention:
+X (Forward)
β²
β
β
+Y (Left) βββββββΌβββββ -Y (Right)
β
β
βΌ
-X (Backward)
Rotation: Counter-clockwise positive (ΞΈ = 0 points to +X)
# config.yaml
grid:
resolution: 0.025 # 2.5cm cells
initial_width: 800 # 20m Γ 20m
initial_height: 800
sensor:
robot:
radius: 0.17 # Robot radius for collision
lidar:
offset_x: -0.110 # LiDAR position relative to robot center
max_range: 8.0
slam:
correlative:
enabled: true
search_x: 0.30 # Β±30cm search window
search_y: 0.30
search_theta: 0.15 # Β±8.6Β° search window
multi_resolution: true
use_gaussian_scoring: true
loop_closure:
enabled: true
min_score_threshold: 0.6use vastu_slam::config::VastuConfig;
use std::path::Path;
// Load from YAML file
let config = VastuConfig::load(Path::new("config.yaml"))?;
// Or use defaults
let config = VastuConfig::default();
// Convert to runtime configs
let map_config = config.to_map_config();
let matcher_config = config.correlative_matcher_config();VastuSLAM uses Structure-of-Arrays (SoA) for SIMD efficiency:
Traditional AoS (Array of Structs):
ββββββββββββββββββββββββββββββββββββββββββββββββββββ
β Cell0{type,conf,swept} β Cell1{...} β Cell2{...} β ...
ββββββββββββββββββββββββββββββββββββββββββββββββββββ
β Cache line may span multiple cells, mixed data types
VastuSLAM SoA (Struct of Arrays):
βββββββββββββββββββββββββββββββββββββββββ
β types: [t0, t1, t2, t3, t4, t5, ...] β β f32x4 SIMD loads
βββββββββββββββββββββββββββββββββββββββββ€
β confs: [c0, c1, c2, c3, c4, c5, ...] β β Contiguous memory
βββββββββββββββββββββββββββββββββββββββββ€
β swept: [s0, s1, s2, s3, s4, s5, ...] β β Cache-friendly
βββββββββββββββββββββββββββββββββββββββββ
| Metric | Typical Value | Notes |
|---|---|---|
| Binary size | ~100KB | Stripped, statically linked |
| Memory (800Γ800) | ~4MB | SoA grid storage |
| Scan matching | 5-15ms | ARM Cortex-A7 @ 1GHz |
| Map save/load | <10ms | Native .vastu format |
| Resolution | 2.5cm | Default, configurable |
# Requires nightly Rust for portable_simd
rustup override set nightly
# Build and test
cargo build --release
cargo testrustup target add armv7-unknown-linux-musleabihf
cargo build --release --target armv7-unknown-linux-musleabihfcargo +nightly doc --no-deps --openuse vastu_slam::{OccupancyGridMap, MapConfig, Pose2D, LidarScan, SensorObservation};
let mut map = OccupancyGridMap::new(MapConfig::default());
// Process complete sensor observation
let observation = SensorObservation {
pose: Pose2D::new(0.0, 0.0, 0.0),
lidar: Some(scan),
cliffs: cliff_sensors,
bumpers: bumper_sensors,
timestamp_us: 0,
};
let result = map.observe(&observation);
println!("Floor: {}, Wall: {}, Cliff: {}, Bump: {}",
result.cells_floor, result.cells_wall,
result.cells_cliff, result.cells_bump);use vastu_slam::{OccupancyGridMap, CorrelativeMatcherConfig};
let mut map = OccupancyGridMap::new(MapConfig::default());
let matcher_config = CorrelativeMatcherConfig::default();
// Match scan and integrate at corrected pose
let (result, corrected_pose, match_result) =
map.observe_lidar_with_matching(&scan, encoder_pose, &matcher_config);
if match_result.converged {
println!("Corrected pose: ({:.3}, {:.3})",
corrected_pose.x, corrected_pose.y);
}use vastu_slam::modes::{Localizer, LocalizerConfig};
use vastu_slam::io::load_vastu;
// Load pre-built map
let map = load_vastu(Path::new("map.vastu"))?;
// Create localizer
let mut localizer = Localizer::new(map, LocalizerConfig::default());
localizer.set_initial_pose(dock_pose);
// Localization loop
let result = localizer.localize(&scan, Some(odom_delta));
if result.converged {
println!("Robot at: ({:.2}, {:.2})", result.pose.x, result.pose.y);
}use vastu_slam::submap::{SubmapManager, SubmapConfig};
let mut manager = SubmapManager::new(SubmapConfig::default(), &map_config);
// Insert scans (manager handles submap transitions)
let result = manager.insert_scan(&scan, pose, timestamp_us);
if result.new_submap_created {
println!("Started new submap");
}
// Get composed global grid
let global_grid = manager.global_grid();| Format | Extension | Purpose | Preserves |
|---|---|---|---|
| Native | .vastu |
Full persistence | All cell data (type, confidence, swept) |
| ROS Map | .pgm + .yaml |
ROS integration | Occupancy only (Free/Occupied/Unknown) |
| SVG | .svg |
Visualization | Visual map + trajectory overlay |
| Type | Thread Safety | Typical Usage |
|---|---|---|
OccupancyGridMap |
Send |
Single-threaded map owner |
GridStorage |
Send |
Single-threaded access |
CorrelativeMatcher |
Send + Sync |
Shared across threads |
SubmapManager |
Send |
Single-threaded manager |
Localizer |
Send |
Single-threaded localizer |
MIT