pax_global_header00006660000000000000000000000064137500763570014527gustar00rootroot0000000000000052 comment=793d06ff51d20fcd94832161ccde268cb4ce5e38 navigation_msgs-1.14.1/000077500000000000000000000000001375007635700150035ustar00rootroot00000000000000navigation_msgs-1.14.1/README.md000066400000000000000000000004111375007635700162560ustar00rootroot00000000000000# Navigation Messages This repository contains messages used by the [navigation stack](https://github.com/ros-planning/navigation). Prior to ROS Jade, these messages were part of that repository. This branch (ros1) is intended for use with ROS Kinetic and above. navigation_msgs-1.14.1/map_msgs/000077500000000000000000000000001375007635700166115ustar00rootroot00000000000000navigation_msgs-1.14.1/map_msgs/CHANGELOG.rst000066400000000000000000000006341375007635700206350ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package map_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.14.1 (2020-11-02) ------------------- 1.14.0 (2020-03-10) ------------------- * Bump CMake version to avoid CMP0048 Signed-off-by: Shane Loretz * Contributors: Shane Loretz 1.13.0 (2015-03-16) ------------------- * initial release from new repository * Contributors: Michael Ferguson navigation_msgs-1.14.1/map_msgs/CMakeLists.txt000066400000000000000000000011671375007635700213560ustar00rootroot00000000000000cmake_minimum_required(VERSION 3.0.2) 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.14.1/map_msgs/msg/000077500000000000000000000000001375007635700173775ustar00rootroot00000000000000navigation_msgs-1.14.1/map_msgs/msg/OccupancyGridUpdate.msg000066400000000000000000000001161375007635700240020ustar00rootroot00000000000000std_msgs/Header header int32 x int32 y uint32 width uint32 height int8[] data navigation_msgs-1.14.1/map_msgs/msg/PointCloud2Update.msg000066400000000000000000000002171375007635700234140ustar00rootroot00000000000000uint32 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.14.1/map_msgs/msg/ProjectedMap.msg000066400000000000000000000000661375007635700224660ustar00rootroot00000000000000nav_msgs/OccupancyGrid map float64 min_z float64 max_znavigation_msgs-1.14.1/map_msgs/msg/ProjectedMapInfo.msg000066400000000000000000000001341375007635700232760ustar00rootroot00000000000000string frame_id float64 x float64 y float64 width float64 height float64 min_z float64 max_znavigation_msgs-1.14.1/map_msgs/package.xml000066400000000000000000000016651375007635700207360ustar00rootroot00000000000000 map_msgs 1.14.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.14.1/map_msgs/srv/000077500000000000000000000000001375007635700174235ustar00rootroot00000000000000navigation_msgs-1.14.1/map_msgs/srv/GetMapROI.srv000066400000000000000000000001161375007635700217040ustar00rootroot00000000000000float64 x float64 y float64 l_x float64 l_y --- nav_msgs/OccupancyGrid sub_mapnavigation_msgs-1.14.1/map_msgs/srv/GetPointMap.srv000066400000000000000000000001131375007635700223410ustar00rootroot00000000000000# Get the map as a sensor_msgs/PointCloud2 --- sensor_msgs/PointCloud2 map navigation_msgs-1.14.1/map_msgs/srv/GetPointMapROI.srv000066400000000000000000000003741375007635700227240ustar00rootroot00000000000000float64 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_mapnavigation_msgs-1.14.1/map_msgs/srv/ProjectedMapsInfo.srv000066400000000000000000000000641375007635700235330ustar00rootroot00000000000000map_msgs/ProjectedMapInfo[] projected_maps_info --- navigation_msgs-1.14.1/map_msgs/srv/SaveMap.srv000066400000000000000000000000761375007635700215160ustar00rootroot00000000000000# Save the map to the filesystem std_msgs/String filename --- navigation_msgs-1.14.1/map_msgs/srv/SetMapProjections.srv000066400000000000000000000000641375007635700235700ustar00rootroot00000000000000--- map_msgs/ProjectedMapInfo[] projected_maps_info navigation_msgs-1.14.1/move_base_msgs/000077500000000000000000000000001375007635700177745ustar00rootroot00000000000000navigation_msgs-1.14.1/move_base_msgs/CHANGELOG.rst000066400000000000000000000012001375007635700220060ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package move_base_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.14.1 (2020-11-02) ------------------- * Merge pull request `#19 `_ from ros-planning/recovery_behavior_msg Recovery behavior msg * Contributors: David V. Lu, David V. Lu!!, Peter Mitrano 1.14.0 (2020-03-10) ------------------- * Bump CMake version to avoid CMP0048 Signed-off-by: Shane Loretz * Contributors: Shane Loretz 1.13.0 (2015-03-16) ------------------- * initial release from new repository * Contributors: Michael Ferguson navigation_msgs-1.14.1/move_base_msgs/CMakeLists.txt000066400000000000000000000007461375007635700225430ustar00rootroot00000000000000cmake_minimum_required(VERSION 3.0.2) project(move_base_msgs) find_package(catkin REQUIRED COMPONENTS actionlib_msgs geometry_msgs message_generation ) # msgs add_message_files( DIRECTORY msg FILES RecoveryStatus.msg ) # actions 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.14.1/move_base_msgs/action/000077500000000000000000000000001375007635700212515ustar00rootroot00000000000000navigation_msgs-1.14.1/move_base_msgs/action/MoveBase.action000066400000000000000000000001261375007635700241500ustar00rootroot00000000000000geometry_msgs/PoseStamped target_pose --- --- geometry_msgs/PoseStamped base_position navigation_msgs-1.14.1/move_base_msgs/msg/000077500000000000000000000000001375007635700205625ustar00rootroot00000000000000navigation_msgs-1.14.1/move_base_msgs/msg/RecoveryStatus.msg000066400000000000000000000005211375007635700242720ustar00rootroot00000000000000geometry_msgs/PoseStamped pose_stamped # The robot's pose when the recovery was triggered uint16 current_recovery_number # 0-based index of current recovery number uint16 total_number_of_recoveries # Total number of recoveries configured string recovery_behavior_name # Namespace of the recovery being executed navigation_msgs-1.14.1/move_base_msgs/package.xml000066400000000000000000000017321375007635700221140ustar00rootroot00000000000000 move_base_msgs 1.14.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