feat(mapping): RTAB-Map persistence + multi-session mapping (Issue #123) #129

Merged
sl-jetson merged 1 commits from sl-perception/issue-123-map-persistence into main 2026-03-02 09:26:29 -05:00
Collaborator

Issue #123 — RTAB-Map Persistence + Multi-Session Mapping

Summary

  • New package saltybot_mapping: MapDatabase, MapExporter, MapManagerNode with 6 ROS2 services
  • Persistence by default: RTAB-Map now loads and continues existing map on every boot; fresh_start:=true arg to start clean
  • Multi-session loop closure: Mem/InitWMWithAllNodes=true loads all prior keyframes for relocalization
  • Auto-save: current.db backed up every 5 min; 5 rotating autosave files kept

Services

/mapping/maps/list           # List all saved .db files with size + mtime
/mapping/maps/save_as        # Copy current.db → <name>.db
/mapping/maps/load           # Swap active DB (requires RTAB-Map restart)
/mapping/maps/delete         # Delete a named map
/mapping/export/occupancy    # Export OccupancyGrid → PGM + YAML
/mapping/export/pointcloud   # Export PointCloud2 → PLY or PCD

Launch args added to slam_rtabmap.launch.py

# Default boot — reload existing map, relocalize, continue
ros2 launch saltybot_bringup slam_rtabmap.launch.py

# Start a fresh map (deletes current.db first)
ros2 launch saltybot_bringup slam_rtabmap.launch.py fresh_start:=true

# Load a specific named map
ros2 launch saltybot_bringup slam_rtabmap.launch.py database_path:=/mnt/nvme/saltybot/maps/home_garden.db

CLI tools

ros2 run saltybot_mapping backup_map -- --name garden_session1
ros2 run saltybot_mapping export_map -- --occupancy --pointcloud --name home --output /tmp

Files changed

  • jetson/config/rtabmap_params.yaml — persistence params block added
  • jetson/ros2_ws/src/saltybot_bringup/launch/slam_rtabmap.launch.py--delete_db_on_start removed, fresh_start + database_path args added, map_manager_node added
  • jetson/ros2_ws/src/saltybot_mapping/ — new package (18 files, 1114 lines)

Test plan

  • colcon build --packages-select saltybot_mapping — zero errors
  • ros2 launch saltybot_bringup slam_rtabmap.launch.py — RTAB-Map loads existing DB, map_manager services available
  • ros2 service call /mapping/maps/list saltybot_mapping/srv/ListMaps — returns map list
  • ros2 service call /mapping/maps/save_as saltybot_mapping/srv/SaveMap '{map_name: test, overwrite: false}'
  • ros2 launch saltybot_bringup slam_rtabmap.launch.py fresh_start:=true — deletes DB, starts fresh
  • ros2 topic echo /mapping/status — JSON status at 1 Hz
  • Autosave: check /mnt/nvme/saltybot/maps/autosave_*.db after 5 min

🤖 Generated with Claude Code

## Issue #123 — RTAB-Map Persistence + Multi-Session Mapping ### Summary - **New package `saltybot_mapping`**: `MapDatabase`, `MapExporter`, `MapManagerNode` with 6 ROS2 services - **Persistence by default**: RTAB-Map now loads and continues existing map on every boot; `fresh_start:=true` arg to start clean - **Multi-session loop closure**: `Mem/InitWMWithAllNodes=true` loads all prior keyframes for relocalization - **Auto-save**: `current.db` backed up every 5 min; 5 rotating autosave files kept ### Services ``` /mapping/maps/list # List all saved .db files with size + mtime /mapping/maps/save_as # Copy current.db → <name>.db /mapping/maps/load # Swap active DB (requires RTAB-Map restart) /mapping/maps/delete # Delete a named map /mapping/export/occupancy # Export OccupancyGrid → PGM + YAML /mapping/export/pointcloud # Export PointCloud2 → PLY or PCD ``` ### Launch args added to slam_rtabmap.launch.py ```bash # Default boot — reload existing map, relocalize, continue ros2 launch saltybot_bringup slam_rtabmap.launch.py # Start a fresh map (deletes current.db first) ros2 launch saltybot_bringup slam_rtabmap.launch.py fresh_start:=true # Load a specific named map ros2 launch saltybot_bringup slam_rtabmap.launch.py database_path:=/mnt/nvme/saltybot/maps/home_garden.db ``` ### CLI tools ```bash ros2 run saltybot_mapping backup_map -- --name garden_session1 ros2 run saltybot_mapping export_map -- --occupancy --pointcloud --name home --output /tmp ``` ### Files changed - `jetson/config/rtabmap_params.yaml` — persistence params block added - `jetson/ros2_ws/src/saltybot_bringup/launch/slam_rtabmap.launch.py` — `--delete_db_on_start` removed, `fresh_start` + `database_path` args added, `map_manager_node` added - `jetson/ros2_ws/src/saltybot_mapping/` — new package (18 files, 1114 lines) ### Test plan - [ ] `colcon build --packages-select saltybot_mapping` — zero errors - [ ] `ros2 launch saltybot_bringup slam_rtabmap.launch.py` — RTAB-Map loads existing DB, map_manager services available - [ ] `ros2 service call /mapping/maps/list saltybot_mapping/srv/ListMaps` — returns map list - [ ] `ros2 service call /mapping/maps/save_as saltybot_mapping/srv/SaveMap '{map_name: test, overwrite: false}'` - [ ] `ros2 launch saltybot_bringup slam_rtabmap.launch.py fresh_start:=true` — deletes DB, starts fresh - [ ] `ros2 topic echo /mapping/status` — JSON status at 1 Hz - [ ] Autosave: check `/mnt/nvme/saltybot/maps/autosave_*.db` after 5 min 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-perception added 1 commit 2026-03-02 09:18:25 -05:00
- Add saltybot_mapping package: MapDatabase, MapExporter, MapManagerNode
- 6 ROS2 services: list/save_as/load/delete maps + export occupancy/pointcloud
- Auto-save current.db every 5 min; keep last 5 autosaves; warn at 2 GB
- Update rtabmap_params.yaml: database_path, Mem/InitWMWithAllNodes=true,
  Rtabmap/StartNewMapOnLoopClosure=false (multi-session persistence by default)
- Update slam_rtabmap.launch.py: remove --delete_db_on_start, add fresh_start
  arg (deletes DB before launch) and database_path arg (load named map)
- CLI tools: backup_map.py, export_map.py

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
sl-jetson merged commit 2e41f05c69 into main 2026-03-02 09:26:29 -05:00
Sign in to join this conversation.
No Reviewers
No Label
1 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#129
No description provided.