This project implements a multi-map navigation system where a robot can navigate between different mapped rooms. Each room is mapped in separate sessions, and a "wormhole" mechanism allows the robot to switch between maps. The system includes:
- π Wormhole-based Map Transitions
- π¦ SQLite database to store map connections
- πΊοΈ Dynamic Map Switching using
map_server
- π€ ROS Action Server for receiving goals
- π€οΈ move_base Integration for local navigation
Imagine a robot in a multi-room facility:
- Each room is mapped separately (e.g., office =
map1
, hallway =map2
, meeting room =map3
). - A user requests the robot to go from office (
map1
) to meeting room (map3
). - The robot:
- Identifies the wormhole path (map1 β map2 β map3)
- Switches maps as needed
- Continues navigation across maps
The system consists of three main components that work together to enable seamless navigation across multiple maps:
- Connects to the SQLite database
- Retrieves wormhole coordinates between maps
- Handles queries to find paths between maps
- Loads map YAML files from the specified directory
- Launches map_server with the appropriate map
- Manages the transition between different environments
- Implements ROS action server for handling navigation goals
- Orchestrates the entire navigation process
- Implements navigation logic for direct and indirect paths
- Utilizes move_base for actual robot movement
multi_map_nav
.
βββ action
βΒ Β βββ NavigateToGoal.action
βββ database
βΒ Β βββ wormholes.db
βββ include
βΒ Β βββ multi_map_nav
βΒ Β βββ map_switcher.h
βΒ Β βββ navigation_server.h
βΒ Β βββ wormhole_manager.h
βββ launch
βΒ Β βββ multi_map_nav.launch
βββ script
βΒ Β βββ action.py
βββ src
β βββ map_switcher.cpp
β βββ navigation_server.cpp
β βββ wormhole_manager.cpp
βββ maps
βΒ Β βββ map1.pgm
βΒ Β βββ map1.yaml
βΒ Β βββ map2.pgm
βΒ Β βββ map2.yaml
βΒ Β βββ map3.pgm
βΒ Β βββ map3.yaml
βββ CMakeLists.txt
βββ package.xml
βββ readme.md
A wormhole is a defined position in one map that links to a corresponding position in another mapβusually an overlapping area such as a doorway or hallway.
- Navigate to the wormhole in the current map.
- Stop the map_server.
- Launch map_server with the target map.
- Teleport the robot to the corresponding wormhole in the new map.
- Resume navigation toward the final goal.
The system receives a navigation request specifying:
-
Target position (x, y)
-
Target map (map_name)
-
If the target is within the current map:
-
Directly forward the goal to move_base
-
If the target is in another map:
-
Initiate multi-map path planning
- Direct Path
-
Check for a direct wormhole from the current map to the target map.
-
If found:
-
Navigate to the wormhole position
-
Switch to the destination map
-
Continue to the target position
-
- Indirect Path (via Central Hub)
-
If no direct path exists:
-
Navigate to a wormhole leading to the central map (map1)
-
Switch to map1
-
Navigate to a wormhole connecting map1 to the target map
-
Switch to the target map
-
Navigate to the final target position
-
-
For each segment:
-
Send a goal to move_base
-
Wait for the result (success/failure)
-
If successful, proceed to the next stage
-
If failed, abort with an error message
-
The wormhole connections are stored in a SQLite database with the following schema:
CREATE TABLE wormholes (
from_map TEXT, -- Source map name
to_map TEXT, -- Destination map name
from_x REAL, -- X-coordinate in source map
from_y REAL -- Y-coordinate in source map
);
Current wormhole connections:
INSERT INTO wormholes VALUES ('map1', 'map2', -1.0, -5.0);
INSERT INTO wormholes VALUES ('map2', 'map1', -1.0, -5.0);
INSERT INTO wormholes VALUES ('map1', 'map3', -1.0, 8.5);
INSERT INTO wormholes VALUES ('map3', 'map1', -1.0, 8.5);
You can view the stored wormhole connections using the sqlite3 command-line tool.
-
π Steps to Open and Query the Database:
sqlite3 wormholes.db
-
Once inside the SQLite prompt, run:
SELECT * FROM wormholes;
-
π Sample Output:
map1|map2|-1.0|-5.0 map2|map1|-1.0|-5.0 map1|map3|-1.0|8.5 map3|map1|-1.0|8.5
Each row represents a wormhole connection:
from_map | to_map | from_x | from_y
NavigateToGoal.action:
# Request
float64 target_x
float64 target_y
string target_map
---
# Result
bool success
string message
---
# Feedback
string feedback_msg
Create a launch file (navigation_server.launch) with the following content:
<launch>
<node pkg="multi_map_nav" type="navigation_server" name="navigation_server" output="screen">
<param name="wormhole_db_path" value="$(find multi_map_nav)/wormholes.db" />
<param name="map_folder" value="$(find multi_map_nav)/maps" />
</node>
</launch>
This allows you to specify paths without hardcoding them in the source code.
cd ~/catkin_ws/src
git clone https://github.com/sherif1152/Multi-Map-Navigation.git
cd ~/catkin_ws
catkin_make
source devel/setup.bash
roslaunch multi_map_nav navigation_server.launch
You can send navigation goals using the ROS action client or directly with rostopic:
-
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: -5.0 target_y: -6.0 target_map: 'map2'"
rostopic pub /navigate_to_goal/goal multi_map_nav/NavigateToGoalActionGoal "goal: target_x: -4.0 target_y: 6.0 target_map: 'map3'"
-
Using Python
Action Client
:#!/usr/bin/env python3 import rospy import actionlib from multi_map_nav.msg import NavigateToGoalAction, NavigateToGoalGoal def send_goal(): client = actionlib.SimpleActionClient('navigate_to_goal', NavigateToGoalAction) client.wait_for_server() goal = NavigateToGoalGoal() goal.target_map = "map2" goal.target_x = 2.5 goal.target_y = 3.0 client.send_goal(goal) client.wait_for_result() return client.get_result() if __name__ == '__main__': rospy.init_node('navigation_client') result = send_goal() print("Result:", result.success, result.message)