SLAM Mapping

Simultaneous Localization and Mapping - Build maps of your environment


Tutorial Overview

🎯 Learning Objectives

By the end of this tutorial, you will:

  • βœ… Understand SLAM concepts and why it's needed

  • βœ… Launch SLAM on Beetlebot

  • βœ… Drive robot to create high-quality maps

  • βœ… Save and load maps

  • βœ… Interpret map quality indicators

  • βœ… Troubleshoot mapping issues

  • βœ… Create maps of different environments

  • βœ… Understand map formats and parameters

⏱️ Time Required

  • Reading & Theory: 25 minutes

  • First Map Creation: 30 minutes

  • Map Quality Practice: 35 minutes

  • Advanced Mapping: 30 minutes

  • Troubleshooting: 20 minutes

  • Total: ~140 minutes

πŸ“š Prerequisites

  • βœ… Completed Sensor Data Visualization

  • βœ… Completed Sensor Fusion with EKF

  • βœ… Can drive robot smoothly

  • βœ… Understanding of LiDAR data

  • βœ… Can use RViz confidently

  • βœ… Environment to map (room, hallway, etc.)

πŸ› οΈ What You'll Need

  • βœ… Beetlebot (fully charged, LiDAR working)

  • βœ… Laptop with ROS2 Jazzy

  • βœ… Wireless controller

  • βœ… Environment with clear features:

    • Walls, furniture, doorways

    • At least 3m Γ— 3m space

    • Avoid glass, mirrors (LiDAR can't see them well)

  • βœ… Patience (good maps take practice!)


Part 1: What is SLAM?

The Chicken-and-Egg Problem

Classic robotics problem:

SLAM Solution: Do BOTH simultaneously!

  • Build map while determining position

  • Use partial map to improve position estimate

  • Use improved position to refine map

  • Iterate continuously


Why SLAM is Hard

Challenges:

  1. Data Association

    • Is this wall same as one seen before?

    • Or a different wall that looks similar?

    • Wrong associations = bad map

  2. Loop Closure

    • Return to previous location after long path

    • Accumulated drift makes it look different

    • Must recognize "I've been here before!"

    • Correct entire trajectory when loop closes

  3. Computational Complexity

    • Tracking thousands of map features

    • Maintaining correlations (covariances)

    • Real-time requirements (robot keeps moving)


SLAM Approaches

Beetlebot uses: SLAM Toolbox (graph-based SLAM)

Other common methods:

  • GMapping - Older, FastSLAM-based (particle filters)

  • Cartographer - Google's SLAM (submap optimization)

  • Hector SLAM - No odometry needed (scan matching only)

  • RTAB-Map - RGB-D SLAM (uses depth cameras)

Why SLAM Toolbox?

  • βœ… Modern, actively maintained

  • βœ… ROS2 native

  • βœ… Real-time capable

  • βœ… Loop closure detection

  • βœ… Map serialization (save/load)

  • βœ… Good for 2D LiDAR


Map Representation

Occupancy Grid Map:

File format: PGM (image) + YAML (metadata)

[PLACEHOLDER: Example map image showing occupied/free/unknown]


Part 2: Your First SLAM Map

Check System Status

Before starting:


Launch SLAM Toolbox

On robot (via SSH or auto-launched):

Your robot likely has SLAM configured to launch automatically. Check:

What launches:

  • slam_toolbox node

  • Subscribes to: /scan, /odometry/filtered

  • Publishes: /map, /map_metadata

  • Provides: Loop closure, graph optimization


Visualize SLAM in RViz

On laptop:

Configure RViz for SLAM:

[PLACEHOLDER: Screenshot of properly configured RViz for SLAM]


Drive Pattern for Good Maps

πŸŽ“ SLAM Driving Best Practices:

DO:

  • βœ… Drive slowly (0.3-0.5 m/s max)

  • βœ… Make long, gentle turns (not sharp 90Β° turns)

  • βœ… Overlap scans (return to previous areas)

  • βœ… Close loops (return to start periodically)

  • βœ… Keep consistent speed (no sudden acceleration)

  • βœ… Drive in open areas first, then details

DON'T:

  • ❌ Drive too fast (>0.8 m/s) - scans don't overlap enough

  • ❌ Make sharp turns - causes scan matching errors

  • ❌ Drive in complete darkness - LiDAR needs features

  • ❌ Go near mirrors/glass - LiDAR passes through

  • ❌ Have moving obstacles during initial mapping


Exercise 8.1: Create Your First Map

Task: Map a single room

Preparation:

Mapping procedure:

Expected time: 3-5 minutes for typical room


Saving Your Map

Once mapping complete:

Files created:

  • my_first_map.pgm - Image file (occupancy grid)

  • my_first_map.yaml - Metadata (resolution, origin, thresholds)


Understanding the Map Files

YAML file (metadata):

Contents:

Key parameters:

resolution: Size of each grid cell

  • Smaller = more detail, larger file

  • Typical: 0.05m (5cm)

  • Range: 0.01-0.10m

origin: Where is (0,0) of image in world coordinates

  • Usually bottom-left corner

  • Negative values = map extends in negative x,y

occupied_thresh: LiDAR hit probability β†’ occupied

  • Higher = more conservative (less marked as obstacle)

  • Lower = more aggressive (more marked as obstacle)

free_thresh: No hit probability β†’ free

  • Higher = more aggressive marking as free

  • Lower = more conservative


Viewing Map Image

Open PGM file:

Image colors:

  • Black pixels: Occupied (walls, obstacles)

  • White pixels: Free space (can drive here)

  • Gray pixels: Unknown (not explored)

[PLACEHOLDER: Example saved map image]


Part 3: Map Quality Assessment

Visual Inspection

Good map indicators:

βœ… Straight walls are straight (not wavy or jagged) βœ… Corners are sharp (90Β° corners clear) βœ… Closed spaces are closed (rooms fully enclosed) βœ… Symmetry preserved (symmetric rooms look symmetric) βœ… Minimal gray (unknown) (most area explored) βœ… No "ghost" walls (false obstacles from bad scans) βœ… Loop closures successful (start/end positions align)


Poor map indicators:

❌ Wavy walls (drove too fast, scan matching failed) ❌ Blurred edges (inconsistent scans, moving during scan) ❌ Disconnected rooms (walls have gaps where shouldn't) ❌ Overlapping walls (double walls, loop closure failed) ❌ Ghost obstacles (artifacts from reflections, moving objects) ❌ Large unknown areas (didn't explore thoroughly)

[PLACEHOLDER: Side-by-side comparison good map vs poor map]


Quantitative Metrics

Check map statistics:

Calculate map coverage:

Good map targets:

  • Free space: 40-60%

  • Occupied: 10-20%

  • Unknown: <30%


Exercise 8.2: Map Quality Comparison

Task: Create two maps of same room, compare quality

Map 1: Fast driving (poor technique)

Map 2: Slow, careful driving (good technique)

Compare:

Expected result: Careful map significantly better!


Part 4: Advanced Mapping Techniques

Multi-Room Mapping

Challenge: Map entire floor with multiple rooms

Strategy:


Loop Closure Detection

What is loop closure?

When robot returns to previously mapped area:

  1. SLAM detects "I've been here before!"

  2. Measures difference between:

    • Where odometry says robot is

    • Where map says robot should be

  3. Adjusts entire trajectory to minimize error

  4. Updates map accordingly

Visual signs of loop closure in RViz:

  • Sudden "snap" of map alignment

  • Previous trajectory may shift slightly

  • Console message: "[INFO] Loop closure detected"


Exercise 8.3: Intentional Loop Closure

Task: Observe loop closure correction

Procedure:


Mapping Large Spaces

For spaces >100mΒ²:

Challenges:

  • Computational load increases

  • Memory requirements grow

  • Loop closure more difficult (more potential matches)

Solutions:

  1. Increase map resolution (larger cells)

  1. Reduce map update rate

  1. Split into submaps

    • Map each area separately

    • Merge offline using map merging tools

  2. Use better computer

    • SLAM runs on robot's Pi 5

    • For huge maps, might need more powerful PC


Part 5: Common Issues and Solutions

Problem: Walls Look Wavy

Cause: Driving too fast, scan matching fails

Solution:


Problem: Map Has Double Walls

Cause: Loop closure failed or didn't happen

Solution:


Problem: Ghost Obstacles

Cause: Reflections (mirrors, glass), moving objects, or sensor noise

Solution:


Problem: Large Gray (Unknown) Areas

Cause: Didn't drive in those areas, or LiDAR obstructed

Solution:


Problem: Map Rotation/Scale Wrong

Cause: TF tree issues, incorrect odometry

Solution:


Part 6: Map Editing and Processing

Cleaning Up Maps

Remove artifacts using GIMP:

Common edits:

  • Remove ghost obstacles (erase black pixels)

  • Close gaps in walls (draw black lines)

  • Clear unknown areas (fill with white if you know it's free)

  • Remove robot from map (sometimes captured in scans)


Adding Virtual Walls

Use case: Prevent robot from entering certain areas


Inflating Obstacles

Add safety margin around obstacles:

Run:


Part 7: Using Maps for Navigation

Loading a Saved Map

For next tutorial (Localization), you'll load maps:

Or use launch file:


Map Server Parameters

Customize map serving:


Part 8: Best Practices Summary

Pre-Mapping Checklist


During Mapping


Post-Mapping


Part 9: Knowledge Check

Concept Quiz

  1. What does SLAM stand for and what does it solve?

  2. Why drive slowly during SLAM?

  3. What is loop closure and why is it important?

  4. What do black, white, and gray pixels mean in map?

  5. Can you create perfect maps without any drift?


Hands-On Challenge

Task: Map a complex environment

Requirements:

  1. Multi-room environment (3+ rooms)

  2. Include hallways, doorways, furniture

  3. Total area >50mΒ²

  4. Complete map in single session (no restarts)

  5. Achieve <25% unknown area

  6. Save final map with documentation

Deliverable:

  • Map files (.pgm + .yaml)

  • Screenshot of map in RViz

  • Statistics (occupied/free/unknown percentages)

  • Written description of environment

  • Notes on challenges encountered

Bonus:

  • Create before/after comparison (initial attempt vs. improved attempt)

  • Edit map to remove artifacts

  • Add inflation layer for safety margins


Part 10: What You've Learned

βœ… Congratulations!

You now understand:

SLAM Fundamentals:

  • βœ… Simultaneous localization and mapping concept

  • βœ… Graph-based SLAM (SLAM Toolbox)

  • βœ… Loop closure detection and correction

  • βœ… Occupancy grid representation

Practical Mapping:

  • βœ… Launching and configuring SLAM

  • βœ… Driving techniques for quality maps

  • βœ… Saving and loading maps

  • βœ… Visual quality assessment

  • βœ… Common issues and solutions

Advanced Topics:

  • βœ… Multi-room mapping strategies

  • βœ… Map editing and processing

  • βœ… Obstacle inflation

  • βœ… Map statistics and metrics


Next Steps

🎯 You're Now Ready For:

Immediate Next: β†’ Localization Techniques - Use saved maps to localize robot

Autonomous Navigation: β†’ Autonomous Navigation - Navigate using your maps

Advanced Mapping:

  • 3D SLAM (if you add depth camera)

  • Outdoor mapping (with GPS fusion)

  • Dynamic environments (handle moving obstacles)

  • Multi-robot SLAM (collaborative mapping)


Quick Reference

Essential SLAM Commands


SLAM Driving Checklist

Action
Speed
Turn Style
Notes

Initial perimeter

0.3-0.5 m/s

Gentle arcs

Define boundaries

Interior coverage

0.3-0.5 m/s

Smooth curves

Fill in details

Loop closures

0.3 m/s

Gentle

Every 2-3 minutes

Final pass

0.3 m/s

Follow previous path

Consistency check


Troubleshooting Flowchart


Completed SLAM Mapping! πŸŽ‰

β†’ Continue to Localization Techniques β†’ Or return to Tutorial Index


Last Updated: January 2026 Tutorial 8 of 11 - Advanced Level Estimated completion time: 140 minutes

Last updated