Skip to content

Commit f48b00d

Browse files
authored
[noetic] Add LoadMap service (#164)
* Add LoadMap service Signed-off-by: Jacob Perron <[email protected]>
1 parent ddb1bbc commit f48b00d

File tree

2 files changed

+17
-1
lines changed

2 files changed

+17
-1
lines changed

nav_msgs/CMakeLists.txt

+2-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,8 @@ add_service_files(
1717
FILES
1818
GetMap.srv
1919
GetPlan.srv
20-
SetMap.srv)
20+
SetMap.srv
21+
LoadMap.srv)
2122

2223
add_action_files(
2324
FILES

nav_msgs/srv/LoadMap.srv

+15
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
# URL of map resource
2+
# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml
3+
# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml
4+
string map_url
5+
---
6+
# Result code defintions
7+
uint8 RESULT_SUCCESS=0
8+
uint8 RESULT_MAP_DOES_NOT_EXIST=1
9+
uint8 RESULT_INVALID_MAP_DATA=2
10+
uint8 RESULT_INVALID_MAP_METADATA=3
11+
uint8 RESULT_UNDEFINED_FAILURE=255
12+
13+
# Returned map is only valid if result equals RESULT_SUCCESS
14+
nav_msgs/OccupancyGrid map
15+
uint8 result

0 commit comments

Comments
 (0)