pax_global_header 0000666 0000000 0000000 00000000064 13553375664 0014533 g ustar 00root root 0000000 0000000 52 comment=3dc18b71094a7037928a8f5470f0f7418c6ce388
navigation_msgs-1.13.1/ 0000775 0000000 0000000 00000000000 13553375664 0015006 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/README.md 0000664 0000000 0000000 00000000375 13553375664 0016272 0 ustar 00root root 0000000 0000000 # Navigation Messages
This repository contains messages used by the
[navigation stack](https://github.com/ros-planning/navigation).
It is intended for use in ROS Jade and above. Prior to Jade some of these
messages existed in the navigation repository. navigation_msgs-1.13.1/map_msgs/ 0000775 0000000 0000000 00000000000 13553375664 0016614 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/map_msgs/CHANGELOG.rst 0000664 0000000 0000000 00000000315 13553375664 0020634 0 ustar 00root root 0000000 0000000 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package map_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
1.13.0 (2015-03-16)
-------------------
* initial release from new repository
* Contributors: Michael Ferguson
navigation_msgs-1.13.1/map_msgs/CMakeLists.txt 0000664 0000000 0000000 00000001167 13553375664 0021361 0 ustar 00root root 0000000 0000000 cmake_minimum_required(VERSION 2.8.3)
project(map_msgs)
find_package(catkin REQUIRED
COMPONENTS
message_generation
nav_msgs
sensor_msgs
std_msgs
)
add_message_files(
FILES
OccupancyGridUpdate.msg
PointCloud2Update.msg
ProjectedMapInfo.msg
ProjectedMap.msg
)
add_service_files(
FILES
GetMapROI.srv
GetPointMapROI.srv
GetPointMap.srv
ProjectedMapsInfo.srv
SaveMap.srv
SetMapProjections.srv
)
generate_messages(
DEPENDENCIES
nav_msgs
sensor_msgs
std_msgs
)
catkin_package(
CATKIN_DEPENDS
message_runtime
nav_msgs
sensor_msgs
std_msgs
)
navigation_msgs-1.13.1/map_msgs/msg/ 0000775 0000000 0000000 00000000000 13553375664 0017402 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/map_msgs/msg/OccupancyGridUpdate.msg 0000664 0000000 0000000 00000000116 13553375664 0024005 0 ustar 00root root 0000000 0000000 std_msgs/Header header
int32 x
int32 y
uint32 width
uint32 height
int8[] data
navigation_msgs-1.13.1/map_msgs/msg/PointCloud2Update.msg 0000664 0000000 0000000 00000000217 13553375664 0023417 0 ustar 00root root 0000000 0000000 uint32 ADD=0
uint32 DELETE=1
std_msgs/Header header
uint32 type # type of update, one of ADD or DELETE
sensor_msgs/PointCloud2 points
navigation_msgs-1.13.1/map_msgs/msg/ProjectedMap.msg 0000664 0000000 0000000 00000000066 13553375664 0022471 0 ustar 00root root 0000000 0000000 nav_msgs/OccupancyGrid map
float64 min_z
float64 max_z navigation_msgs-1.13.1/map_msgs/msg/ProjectedMapInfo.msg 0000664 0000000 0000000 00000000134 13553375664 0023301 0 ustar 00root root 0000000 0000000 string frame_id
float64 x
float64 y
float64 width
float64 height
float64 min_z
float64 max_z navigation_msgs-1.13.1/map_msgs/package.xml 0000664 0000000 0000000 00000001665 13553375664 0020741 0 ustar 00root root 0000000 0000000
map_msgs
1.13.1
This package defines messages commonly used in mapping packages.
Stéphane Magnenat
David V. Lu!!
Michael Ferguson
BSD
http://ros.org/wiki/map_msgs
https://github.com/ros-planning/navigation_msgs/issues
catkin
message_generation
nav_msgs
sensor_msgs
std_msgs
message_runtime
nav_msgs
sensor_msgs
std_msgs
navigation_msgs-1.13.1/map_msgs/srv/ 0000775 0000000 0000000 00000000000 13553375664 0017426 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/map_msgs/srv/GetMapROI.srv 0000664 0000000 0000000 00000000116 13553375664 0021707 0 ustar 00root root 0000000 0000000 float64 x
float64 y
float64 l_x
float64 l_y
---
nav_msgs/OccupancyGrid sub_map navigation_msgs-1.13.1/map_msgs/srv/GetPointMap.srv 0000664 0000000 0000000 00000000113 13553375664 0022344 0 ustar 00root root 0000000 0000000 # Get the map as a sensor_msgs/PointCloud2
---
sensor_msgs/PointCloud2 map
navigation_msgs-1.13.1/map_msgs/srv/GetPointMapROI.srv 0000664 0000000 0000000 00000000374 13553375664 0022727 0 ustar 00root root 0000000 0000000 float64 x
float64 y
float64 z
float64 r # if != 0, circular ROI of radius r
float64 l_x # if r == 0, length of AABB on x
float64 l_y # if r == 0, length of AABB on y
float64 l_z # if r == 0, length of AABB on z
---
sensor_msgs/PointCloud2 sub_map navigation_msgs-1.13.1/map_msgs/srv/ProjectedMapsInfo.srv 0000664 0000000 0000000 00000000064 13553375664 0023536 0 ustar 00root root 0000000 0000000 map_msgs/ProjectedMapInfo[] projected_maps_info
---
navigation_msgs-1.13.1/map_msgs/srv/SaveMap.srv 0000664 0000000 0000000 00000000076 13553375664 0021521 0 ustar 00root root 0000000 0000000 # Save the map to the filesystem
std_msgs/String filename
---
navigation_msgs-1.13.1/map_msgs/srv/SetMapProjections.srv 0000664 0000000 0000000 00000000064 13553375664 0023573 0 ustar 00root root 0000000 0000000 ---
map_msgs/ProjectedMapInfo[] projected_maps_info
navigation_msgs-1.13.1/move_base_msgs/ 0000775 0000000 0000000 00000000000 13553375664 0017777 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/move_base_msgs/CHANGELOG.rst 0000664 0000000 0000000 00000000337 13553375664 0022023 0 ustar 00root root 0000000 0000000 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package move_base_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
1.13.0 (2015-03-16)
-------------------
* initial release from new repository
* Contributors: Michael Ferguson
navigation_msgs-1.13.1/move_base_msgs/CMakeLists.txt 0000664 0000000 0000000 00000000614 13553375664 0022540 0 ustar 00root root 0000000 0000000 cmake_minimum_required(VERSION 2.8.3)
project(move_base_msgs)
find_package(catkin REQUIRED
COMPONENTS
actionlib_msgs
geometry_msgs
message_generation
)
add_action_files(
DIRECTORY
action
FILES
MoveBase.action
)
generate_messages(
DEPENDENCIES
actionlib_msgs
geometry_msgs
)
catkin_package(
CATKIN_DEPENDS actionlib_msgs geometry_msgs message_runtime
)
navigation_msgs-1.13.1/move_base_msgs/action/ 0000775 0000000 0000000 00000000000 13553375664 0021254 5 ustar 00root root 0000000 0000000 navigation_msgs-1.13.1/move_base_msgs/action/MoveBase.action 0000664 0000000 0000000 00000000126 13553375664 0024153 0 ustar 00root root 0000000 0000000 geometry_msgs/PoseStamped target_pose
---
---
geometry_msgs/PoseStamped base_position
navigation_msgs-1.13.1/move_base_msgs/package.xml 0000664 0000000 0000000 00000001732 13553375664 0022117 0 ustar 00root root 0000000 0000000
move_base_msgs
1.13.1
Holds the action description and relevant messages for the move_base package.
Eitan Marder-Eppstein
contradict@gmail.com
David V. Lu!!
Michael Ferguson
BSD
http://wiki.ros.org/move_base_msgs
https://github.com/ros-planning/navigation_msgs/issues
catkin
actionlib_msgs
geometry_msgs
message_generation
actionlib_msgs
geometry_msgs
message_runtime