This repository demonstrates multi-map, multi-room autonomous navigation using wormhole-based transitions on the AR100 robot by Anscer Robotics, tested in a custom multi-room environment.
🎥 Click to view full video demo
- OS: Ubuntu 20.04
- ROS: ROS Noetic
- Editor: VSCode
- Build System: Catkin
-
Install AR100 simulation
Follow the instructions from the official Anscer AR100 repository. -
Replace with Custom World
- Use the provided
World/folder (3-room setup). - Replace
map.pgmandmap.yamlinanscer_navigation/maps/withmap1.pgmandmap1.yamlfrom this repo and rename them to the default names.
- Use the provided
cd ~/catkin_ws/src
git clone https://github.com/jerinpeter/ar100-multimap-nav.gitcd ~/catkin_ws
catkin_make
source devel/setup.bashroslaunch multi_map_nav navigation_server.launchNote: Ensure
anscer_navigationis running before launching the navigation server.
You can publish a goal manually using rostopic:
rostopic pub /navigate_to_goal/goal multi_map_nav/NavigateToGoalActionGoal "header:
seq: 0
stamp: {secs: 0, nsecs: 0}
frame_id: ''
goal_id:
stamp: {secs: 0, nsecs: 0}
id: ''
goal:
target_x: -6.0
target_y: -4.0
target_map: 'map2'"You can also publish a goal using the PyQT GUI
rosrun multi_map_nav LaunchUi.py
specify the map name as well as the target x and y coordinates
The SQLite database stores all wormhole connections:
CREATE TABLE wormholes (
from_map TEXT,
to_map TEXT,
from_x REAL,
from_y REAL
);| from_map | to_map | from_x | from_y |
|---|---|---|---|
| map1 | map2 | -7.8 | 1.2 |
| map2 | map1 | -7.8 | 1.0 |
| map1 | map3 | 8.5 | 2.5 |
| map3 | map1 | 8.5 | 2.5 |
NavigateToGoal.action
# Goal
float64 target_x
float64 target_y
string target_map
---
# Result
bool success
string message
---
# Feedback
string feedback_msg- Connects to SQLite DB to retrieve wormhole data.
- Computes direct/indirect transitions between maps.
- Enables seamless planning across environments.
- Loads
.pgm/.yamlmap files. - Dynamically controls
map_serverfor each transition. - Resets localization when switching.
- Custom ROS Action Server.
- Accepts goal with target (x, y) and map name.
- Decides if direct
move_basecall is enough or wormhole is needed.
Receives:
- Coordinates (x, y)
- Target map name
- If goal is in current map → directly use
move_base. - Else → use wormhole path planning.
- Go to wormhole in current map.
- Switch map.
- Continue to target.
Heading to wormhole (map2 → map1)
Map1 activated, final goal reached
- Navigate to hub.
- Switch to next wormhole.
- Go to final location.
- 🛣️ Wormhole navigation across rooms/maps
- 💾 SQLite for persistent wormhole mapping
- 🔄 Dynamic map switching using
map_server - ⚙️ Full integration with
move_base - 🛰️ Actionlib interface for goal delivery
- 🧩 Modular architecture for scalability
- Orientation of the robot is always set to
M_PI/2which creates akward transistion between wormholes and the rooms. - Can be solved by echoing current orientation and stopping at that, wait for map switch then continue navigation.
- Can add validity check for the waypoints, Even though the robot navigates to the correct room/map, I have not implemented a logic to check if the given coordinates are inside the map (not out of bounds).
- Can add Preemption handling, In the current implementation, if a goal is given another one can't be given until this is finished
| Requirement | Status |
|---|---|
| 1. Video Demonstration | ✅ Yes |
| 2. C++ Source Code | ✅ Yes |
| 3a. Key files listed | ✅ Yes |
| 3b. Build & launch instructions | ✅ Yes |
| 3c. Algorithm explained | ✅ Yes |
| 3d. Unimplemented parts mentioned | ✅ Yes |
navigation_server.cpp— Handles navigation requests & manages transitionsmap_switcher.cpp— Switches map usingmap_serverwormhole_manager.cpp— Loads DB & determines routeslaunch/— Startup configurationsmedia/— Simulation imagesREADME.md— You’re reading it!
This project provides a modular and scalable framework for multi-environment navigation using ROS and SQLite, ideal for smart facilities, research robots, or warehouse AMRs.



