Skip to content

Commit

Permalink
Fix problem with CMAKE_PREFIX_PATH (#352)
Browse files Browse the repository at this point in the history
* Reorder find_package(catkin) to fix problem with CMAKE_PREFIX_PATH
For details, see #351

* Fix name of PCL component (common, not core)
  • Loading branch information
mvieth authored Dec 15, 2021
1 parent 8969ea6 commit d04a2b3
Showing 1 changed file with 23 additions and 23 deletions.
46 changes: 23 additions & 23 deletions pcl_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,30 @@ else()
set(CMAKE_CXX_STANDARD 14)
endif()

## Find catkin packages
find_package(catkin REQUIRED COMPONENTS
dynamic_reconfigure
geometry_msgs
message_filters
nodelet
nodelet_topic_tools
pcl_conversions
pcl_msgs
pluginlib
rosbag
rosconsole
roscpp
roslib
sensor_msgs
std_msgs
tf
tf2
tf2_eigen
tf2_ros
)

## Find system dependencies
find_package(PCL REQUIRED COMPONENTS core features filters io segmentation surface)
find_package(PCL REQUIRED COMPONENTS common features filters io segmentation surface)
find_package(Boost REQUIRED COMPONENTS system filesystem thread)
find_package(Eigen3 REQUIRED)

Expand Down Expand Up @@ -41,28 +63,6 @@ if(NOT "${PCL_INCLUDE_DIRS}" STREQUAL "")
endforeach()
endif()

## Find catkin packages
find_package(catkin REQUIRED COMPONENTS
dynamic_reconfigure
geometry_msgs
message_filters
nodelet
nodelet_topic_tools
pcl_conversions
pcl_msgs
pluginlib
rosbag
rosconsole
roscpp
roslib
sensor_msgs
std_msgs
tf
tf2
tf2_eigen
tf2_ros
)

## Add include directories
include_directories(include)

Expand Down

0 comments on commit d04a2b3

Please sign in to comment.