From cbbd88b04ef887268ba4464fddabd6b4e2de4d53 Mon Sep 17 00:00:00 2001 From: Andrew Hundt Date: Wed, 13 Apr 2016 15:40:21 -0400 Subject: [PATCH] OpenNI2 pkg_config replaced with find script from PCL. Compilation now works on OS X. --- CMakeLists.txt | 30 +++---- cmake/FindOpenNI2.cmake | 80 +++++++++++++++++++ include/openni2_camera/openni2_convert.h | 2 +- .../openni2_camera/openni2_frame_listener.h | 2 +- include/openni2_camera/openni2_timer_filter.h | 2 +- src/openni2_device.cpp | 2 +- src/openni2_device_manager.cpp | 2 +- src/openni2_frame_listener.cpp | 2 +- 8 files changed, 101 insertions(+), 21 deletions(-) create mode 100644 cmake/FindOpenNI2.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 0034ba8..b4949fd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,16 +1,14 @@ cmake_minimum_required(VERSION 2.8.3) project(openni2_camera) +set(CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) + find_package(catkin REQUIRED camera_info_manager dynamic_reconfigure image_transport nodelet sensor_msgs roscpp message_generation) find_package(Boost REQUIRED COMPONENTS system thread) -find_package(PkgConfig) +find_package(OpenNI2 REQUIRED) -pkg_check_modules(PC_OPENNI2 libopenni2) -if (NOT PC_OPENNI2_FOUND) - pkg_check_modules(PC_OPENNI2 REQUIRED openni2) -endif() generate_dynamic_reconfigure_options(cfg/OpenNI2.cfg) add_service_files(FILES @@ -26,12 +24,10 @@ catkin_package( include_directories(include ${catkin_INCLUDE_DIRS} - ${Boost_INCLUDE_DIRS} - ${PC_OPENNI2_INCLUDE_DIRS} + ${Boost_ICLUDE_DIRS} + ${OPENNI2_INCLUDE_DIRS} ) -link_directories(${PC_OPENNI2_LIBRARY_DIRS}) - add_library(openni2_wrapper src/openni2_convert.cpp src/openni2_device.cpp @@ -42,33 +38,37 @@ add_library(openni2_wrapper src/openni2_exception.cpp src/openni2_video_mode.cpp ) -target_link_libraries(openni2_wrapper ${catkin_LIBRARIES} ${PC_OPENNI2_LIBRARIES} ${Boost_LIBRARIES} ) +target_link_libraries(openni2_wrapper + ${catkin_LIBRARIES} + ${OPENNI2_LIBRARIES} + ${Boost_LIBRARIES} +) add_executable(test_wrapper test/test_wrapper.cpp ) -target_link_libraries(test_wrapper openni2_wrapper ${Boost_LIBRARIES}) +target_link_libraries(test_wrapper openni2_wrapper ${Boost_LIBRARIES} ${OPENNI2_LIBRARIES}) add_library(openni2_driver_lib src/openni2_driver.cpp ) -target_link_libraries(openni2_driver_lib openni2_wrapper ${catkin_LIBRARIES} ${Boost_LIBRARIES} ) +target_link_libraries(openni2_driver_lib openni2_wrapper ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${OPENNI2_LIBRARIES}) add_dependencies(openni2_driver_lib ${PROJECT_NAME}_gencfg) add_library(openni2_camera_nodelet ros/openni2_camera_nodelet.cpp ) -target_link_libraries(openni2_camera_nodelet openni2_driver_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ) +target_link_libraries(openni2_camera_nodelet openni2_driver_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${OPENNI2_LIBRARIES}) add_dependencies(openni2_camera_nodelet ${PROJECT_NAME}_gencfg) add_executable(openni2_camera_node ros/openni2_camera_node.cpp ) -target_link_libraries(openni2_camera_node openni2_driver_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ) +target_link_libraries(openni2_camera_node openni2_driver_lib ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${OPENNI2_LIBRARIES}) add_dependencies(openni2_camera_node ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_generate_messages_cpp) add_executable(list_devices src/list_devices.cpp ) -target_link_libraries(list_devices openni2_wrapper) +target_link_libraries(list_devices openni2_wrapper ${OPENNI2_LIBRARIES}) if (UNIX AND NOT APPLE) add_executable(usb_reset src/usb_reset.c) diff --git a/cmake/FindOpenNI2.cmake b/cmake/FindOpenNI2.cmake new file mode 100644 index 0000000..713099a --- /dev/null +++ b/cmake/FindOpenNI2.cmake @@ -0,0 +1,80 @@ +############################################################################### +# Find OpenNI 2 +# +# This sets the following variables: +# OPENNI2_FOUND - True if OPENNI 2 was found. +# OPENNI2_INCLUDE_DIRS - Directories containing the OPENNI 2 include files. +# OPENNI2_LIBRARIES - Libraries needed to use OPENNI 2. +# OPENNI2_DEFINITIONS - Compiler flags for OPENNI 2. +# +# For libusb-1.0, add USB_10_ROOT if not found + +find_package(PkgConfig QUIET) + +# Find LibUSB +if(NOT WIN32) + pkg_check_modules(PC_USB_10 libusb-1.0) + find_path(USB_10_INCLUDE_DIR libusb-1.0/libusb.h + HINTS ${PC_USB_10_INCLUDEDIR} ${PC_USB_10_INCLUDE_DIRS} "${USB_10_ROOT}" "$ENV{USB_10_ROOT}" + PATH_SUFFIXES libusb-1.0) + + find_library(USB_10_LIBRARY + NAMES usb-1.0 + HINTS ${PC_USB_10_LIBDIR} ${PC_USB_10_LIBRARY_DIRS} "${USB_10_ROOT}" "$ENV{USB_10_ROOT}" + PATH_SUFFIXES lib) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(USB_10 DEFAULT_MSG USB_10_LIBRARY USB_10_INCLUDE_DIR) + + if(NOT USB_10_FOUND) + message(STATUS "OpenNI 2 disabled because libusb-1.0 not found.") + return() + else() + include_directories(SYSTEM ${USB_10_INCLUDE_DIR}) + endif() +endif(NOT WIN32) + +if(${CMAKE_VERSION} VERSION_LESS 2.8.2) + pkg_check_modules(PC_OPENNI2 libopenni2) +else() + pkg_check_modules(PC_OPENNI2 QUIET libopenni2) +endif() + +set(OPENNI2_DEFINITIONS ${PC_OPENNI_CFLAGS_OTHER}) + +set(OPENNI2_SUFFIX) +if(WIN32 AND CMAKE_SIZEOF_VOID_P EQUAL 8) + set(OPENNI2_SUFFIX 64) +endif(WIN32 AND CMAKE_SIZEOF_VOID_P EQUAL 8) + +find_path(OPENNI2_INCLUDE_DIRS OpenNI.h + PATHS + "$ENV{OPENNI2_INCLUDE${OPENNI2_SUFFIX}}" # Win64 needs '64' suffix + /usr/include/openni2 # common path for deb packages +) + +find_library(OPENNI2_LIBRARY + NAMES OpenNI2 # No suffix needed on Win64 + libOpenNI2 # Linux + PATHS "$ENV{OPENNI2_LIB${OPENNI2_SUFFIX}}" # Windows default path, Win64 needs '64' suffix + "$ENV{OPENNI2_REDIST}" # Linux install does not use a separate 'lib' directory + ) + +if(CMAKE_SYSTEM_NAME STREQUAL "Darwin") + set(OPENNI2_LIBRARIES ${OPENNI2_LIBRARY} ${LIBUSB_1_LIBRARIES}) +else() + set(OPENNI2_LIBRARIES ${OPENNI2_LIBRARY}) +endif() + +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(OpenNI2 DEFAULT_MSG OPENNI2_LIBRARY OPENNI2_INCLUDE_DIRS) + +mark_as_advanced(OPENNI2_LIBRARY OPENNI2_INCLUDE_DIRS) + +if(OPENNI2_FOUND) + # Add the include directories + set(OPENNI2_INCLUDE_DIRS ${OPENNI2_INCLUDE_DIR}) + set(OPENNI2_REDIST_DIR $ENV{OPENNI2_REDIST${OPENNI2_SUFFIX}}) + message(STATUS "OpenNI 2 found (include: ${OPENNI2_INCLUDE_DIRS}, lib: ${OPENNI2_LIBRARY}, redist: ${OPENNI2_REDIST_DIR})") +endif(OPENNI2_FOUND) + diff --git a/include/openni2_camera/openni2_convert.h b/include/openni2_camera/openni2_convert.h index ff1edaf..9949def 100644 --- a/include/openni2_camera/openni2_convert.h +++ b/include/openni2_camera/openni2_convert.h @@ -36,7 +36,7 @@ #include "openni2_camera/openni2_device_info.h" #include "openni2_camera/openni2_video_mode.h" -#include "OpenNI.h" +#include "ni2/OpenNI.h" #include diff --git a/include/openni2_camera/openni2_frame_listener.h b/include/openni2_camera/openni2_frame_listener.h index 3338042..6120362 100644 --- a/include/openni2_camera/openni2_frame_listener.h +++ b/include/openni2_camera/openni2_frame_listener.h @@ -38,7 +38,7 @@ #include -#include "OpenNI.h" +#include "ni2/OpenNI.h" namespace openni2_wrapper { diff --git a/include/openni2_camera/openni2_timer_filter.h b/include/openni2_camera/openni2_timer_filter.h index e488337..c3fc50d 100644 --- a/include/openni2_camera/openni2_timer_filter.h +++ b/include/openni2_camera/openni2_timer_filter.h @@ -34,7 +34,7 @@ #include -#include "OpenNI.h" +#include "ni2/OpenNI.h" namespace openni2_wrapper { diff --git a/src/openni2_device.cpp b/src/openni2_device.cpp index 10a1828..e95ae20 100644 --- a/src/openni2_device.cpp +++ b/src/openni2_device.cpp @@ -29,7 +29,7 @@ * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#include "OpenNI.h" +#include "ni2/OpenNI.h" #include #include diff --git a/src/openni2_device_manager.cpp b/src/openni2_device_manager.cpp index c2a0416..fe0537f 100644 --- a/src/openni2_device_manager.cpp +++ b/src/openni2_device_manager.cpp @@ -41,7 +41,7 @@ #include #include -#include "OpenNI.h" +#include "ni2/OpenNI.h" namespace openni2_wrapper { diff --git a/src/openni2_frame_listener.cpp b/src/openni2_frame_listener.cpp index 40cd627..0d14c4b 100644 --- a/src/openni2_frame_listener.cpp +++ b/src/openni2_frame_listener.cpp @@ -28,7 +28,7 @@ * * Author: Julius Kammerl (jkammerl@willowgarage.com) */ -#include "OpenNI.h" +#include "ni2/OpenNI.h" #include "openni2_camera/openni2_frame_listener.h" #include "openni2_camera/openni2_timer_filter.h"