pax_global_header00006660000000000000000000000064136337656070014532gustar00rootroot0000000000000052 comment=ddcc8e14729f0b3b2dca21c4be463fe65fa72c65 pcl_msgs-0.3.0/000077500000000000000000000000001363376560700133415ustar00rootroot00000000000000pcl_msgs-0.3.0/CHANGELOG.rst000066400000000000000000000014141363376560700153620ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package pcl_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.2.0 (2014-04-09) ------------------ * clean up package.xml * update maintainer info * remove eigen dependency * Merge pull request `#1 `_ from bulwahn/patch-1 * Contributors: Lukas Bulwahn, Paul Bovbel 0.1.0 (2013-07-09) ------------------ * Generate messages into the pcl_msgs namespace rather than the pcl namespace 0.0.3 (2012-12-15) ------------------ * fix deps for messages * Updated for new catkin<...> rule 0.0.2 (2012-11-26 18:50) ------------------------ * increasing version * ros message generation prefix hack 0.0.1 (2012-11-26 17:48) ------------------------ * initial commit - pcl ROS messages pcl_msgs-0.3.0/CMakeLists.txt000066400000000000000000000010741363376560700161030ustar00rootroot00000000000000cmake_minimum_required(VERSION 3.0.2) project(pcl_msgs) # Deal with catkin find_package(catkin REQUIRED COMPONENTS message_generation sensor_msgs std_msgs) # create messages add_message_files(DIRECTORY msg FILES ModelCoefficients.msg PointIndices.msg PolygonMesh.msg Vertices.msg ) add_service_files(DIRECTORY srv FILES UpdateFilename.srv) generate_messages(DEPENDENCIES sensor_msgs std_msgs) catkin_package(CATKIN_DEPENDS message_runtime sensor_msgs std_msgs) pcl_msgs-0.3.0/README.md000066400000000000000000000001001363376560700146070ustar00rootroot00000000000000pcl_msgs ======== ROS package containing PCL-related messages pcl_msgs-0.3.0/msg/000077500000000000000000000000001363376560700141275ustar00rootroot00000000000000pcl_msgs-0.3.0/msg/ModelCoefficients.msg000066400000000000000000000000401363376560700202130ustar00rootroot00000000000000Header header float32[] values pcl_msgs-0.3.0/msg/PointIndices.msg000066400000000000000000000000371363376560700172270ustar00rootroot00000000000000Header header int32[] indices pcl_msgs-0.3.0/msg/PolygonMesh.msg000066400000000000000000000002471363376560700171060ustar00rootroot00000000000000# Separate header for the polygonal surface Header header # Vertices of the mesh as a point cloud sensor_msgs/PointCloud2 cloud # List of polygons Vertices[] polygons pcl_msgs-0.3.0/msg/Vertices.msg000066400000000000000000000000521363376560700164200ustar00rootroot00000000000000# List of point indices uint32[] vertices pcl_msgs-0.3.0/package.xml000066400000000000000000000017731363376560700154660ustar00rootroot00000000000000 pcl_msgs 0.3.0 Package containing PCL (Point Cloud Library)-related ROS messages. Open Perception Julius Kammerl William Woodall Paul Bovbel Bill Morris BSD http://wiki.ros.org/pcl_msgs https://github.com/ros-perception/pcl_msgs https://github.com/ros-perception/pcl_msgs/issues catkin message_generation sensor_msgs std_msgs message_runtime sensor_msgs std_msgs pcl_msgs-0.3.0/srv/000077500000000000000000000000001363376560700141535ustar00rootroot00000000000000pcl_msgs-0.3.0/srv/UpdateFilename.srv000066400000000000000000000000411363376560700175650ustar00rootroot00000000000000string filename --- bool success