Skip to content

Commit

Permalink
[noetic] Add LoadMap service (#164)
Browse files Browse the repository at this point in the history
* Add LoadMap service

Signed-off-by: Jacob Perron <[email protected]>
  • Loading branch information
DLu authored Aug 13, 2020
1 parent ddb1bbc commit f48b00d
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 1 deletion.
3 changes: 2 additions & 1 deletion nav_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@ add_service_files(
FILES
GetMap.srv
GetPlan.srv
SetMap.srv)
SetMap.srv
LoadMap.srv)

add_action_files(
FILES
Expand Down
15 changes: 15 additions & 0 deletions nav_msgs/srv/LoadMap.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
# URL of map resource
# Can be an absolute path to a file: file:///path/to/maps/floor1.yaml
# Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml
string map_url
---
# Result code defintions
uint8 RESULT_SUCCESS=0
uint8 RESULT_MAP_DOES_NOT_EXIST=1
uint8 RESULT_INVALID_MAP_DATA=2
uint8 RESULT_INVALID_MAP_METADATA=3
uint8 RESULT_UNDEFINED_FAILURE=255

# Returned map is only valid if result equals RESULT_SUCCESS
nav_msgs/OccupancyGrid map
uint8 result

0 comments on commit f48b00d

Please sign in to comment.