bring back the PCL msgs
This commit is contained in:
parent
a5c158904d
commit
e677ddf794
@ -2,13 +2,17 @@ cmake_minimum_required(VERSION 2.8)
|
||||
project(pcl_ros)
|
||||
|
||||
# Deal with catkin
|
||||
find_package(catkin REQUIRED roscpp sensor_msgs tf)
|
||||
find_package(Boost COMPONENTS system filesystem thread REQUIRED)
|
||||
find_package(catkin REQUIRED genmsg roscpp sensor_msgs std_msgs tf)
|
||||
find_package(Eigen)
|
||||
find_package(PCL)
|
||||
|
||||
# deal with ROS
|
||||
include_directories(${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} ${Eigen_INCLUDE_DIRS} ${PCL_INCLUDE_DIRS})
|
||||
include_directories(SYSTEM ${Boost_INCLUDE_DIRS}
|
||||
${catkin_INCLUDE_DIRS}
|
||||
${Eigen_INCLUDE_DIRS}
|
||||
${PCL_INCLUDE_DIRS}
|
||||
)
|
||||
include_directories(include)
|
||||
|
||||
link_directories(${catkin_LIBRARY_DIRS} ${Boost_LIBRARY_DIRS} ${Eigen_LIBRARY_DIRS} ${PCL_LIBRARY_DIRS})
|
||||
@ -18,9 +22,21 @@ catkin_package(DEPENDS Eigen PCL roscpp sensor_msgs tf
|
||||
LIBRARIES pcl_ros_tf
|
||||
)
|
||||
|
||||
# create messages
|
||||
project(pcl)
|
||||
add_message_files(DIRECTORY msg
|
||||
FILES ModelCoefficients.msg
|
||||
PointIndices.msg
|
||||
PolygonMesh.msg
|
||||
Vertices.msg
|
||||
)
|
||||
generate_messages(DEPENDENCIES sensor_msgs std_msgs)
|
||||
|
||||
project(pcl_ros)
|
||||
# ---[ Point Cloud Library - Transforms
|
||||
add_library (pcl_ros_tf SHARED src/transforms.cpp)
|
||||
target_link_libraries(pcl_ros_tf ${PCL_LIBS} ${Boost_LIBS} ${catkin_LIBS})
|
||||
add_dependencies(pcl_ros_tf ros_gencpp pcl_ros_copy)
|
||||
|
||||
install(DIRECTORY include/${PROJECT_NAME}/
|
||||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
|
||||
|
||||
3
pcl_ros/msg/ModelCoefficients.msg
Normal file
3
pcl_ros/msg/ModelCoefficients.msg
Normal file
@ -0,0 +1,3 @@
|
||||
Header header
|
||||
float32[] values
|
||||
|
||||
3
pcl_ros/msg/PointIndices.msg
Normal file
3
pcl_ros/msg/PointIndices.msg
Normal file
@ -0,0 +1,3 @@
|
||||
Header header
|
||||
int32[] indices
|
||||
|
||||
6
pcl_ros/msg/PolygonMesh.msg
Normal file
6
pcl_ros/msg/PolygonMesh.msg
Normal file
@ -0,0 +1,6 @@
|
||||
# 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
|
||||
2
pcl_ros/msg/Vertices.msg
Normal file
2
pcl_ros/msg/Vertices.msg
Normal file
@ -0,0 +1,2 @@
|
||||
# List of point indices
|
||||
uint32[] vertices
|
||||
@ -22,6 +22,7 @@
|
||||
<build_depend>pcl</build_depend>
|
||||
<build_depend>roscpp</build_depend>
|
||||
<build_depend>sensor_msgs</build_depend>
|
||||
<build_depend>std_msgs</build_depend>
|
||||
<build_depend>tf</build_depend>
|
||||
|
||||
<run_depend>common_msgs</run_depend>
|
||||
@ -30,5 +31,6 @@
|
||||
<run_depend>pcl</run_depend>
|
||||
<run_depend>roscpp</run_depend>
|
||||
<run_depend>sensor_msgs</run_depend>
|
||||
<run_depend>std_msgs</run_depend>
|
||||
<run_depend>tf</run_depend>
|
||||
</package>
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user