From 16fe2a02ee50ae24f7d78fa6d1230d1d0a9f6a10 Mon Sep 17 00:00:00 2001 From: Nikolaus Demmel Date: Tue, 10 Jun 2014 23:14:41 +0200 Subject: [PATCH] Some cleanup in package.xml and CMakeLists.txt MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - builds broke sporadically (I think because of the missing *_gencpp in add_dependencies) with missing Packet.h file. - I’m no catkin expert, but these changes make catkin_lint happy (no more errors at least). --- theora_image_transport/CMakeLists.txt | 8 +++----- theora_image_transport/package.xml | 3 ++- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/theora_image_transport/CMakeLists.txt b/theora_image_transport/CMakeLists.txt index dddf153..4b291d9 100644 --- a/theora_image_transport/CMakeLists.txt +++ b/theora_image_transport/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(theora_image_transport) find_package(OpenCV REQUIRED) -find_package(catkin REQUIRED cv_bridge dynamic_reconfigure image_transport message_generation tf rosbag) +find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure image_transport message_generation tf rosbag pluginlib std_msgs) add_message_files(DIRECTORY msg FILES Packet.msg) @@ -21,7 +21,7 @@ generate_dynamic_reconfigure_options(cfg/TheoraPublisher.cfg cfg/TheoraSubscribe catkin_package( INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME} - CATKIN_DEPENDS message_runtime + CATKIN_DEPENDS message_runtime std_msgs ) include_directories(include ${catkin_INCLUDE_DIRS}) @@ -43,20 +43,18 @@ add_definitions(${PC_OGG_CFLAGS_OTHER} ) add_library(${PROJECT_NAME} src/theora_publisher.cpp src/theora_subscriber.cpp src/manifest.cpp) -add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg) +add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_gencfg ${PROJECT_NAME}_gencpp) target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${PC_OGG_LIBRARIES} ${PC_THEORA_LIBRARIES} ${PC_THEORAENC_LIBRARIES} ${PC_THEORADEC_LIBRARIES} -# ogg theora theoraenc theoradec ) class_loader_hide_library_symbols(${PROJECT_NAME}) add_executable(ogg_saver src/ogg_saver.cpp) -include_directories(ogg_saver include cfg/cpp) target_link_libraries(ogg_saver ${PC_THEORA_LIBRARY} ${PC_OGG_LIBRARY} ${OpenCV_LIBRARIES} diff --git a/theora_image_transport/package.xml b/theora_image_transport/package.xml index c6f8589..116ebc5 100644 --- a/theora_image_transport/package.xml +++ b/theora_image_transport/package.xml @@ -23,6 +23,7 @@ pluginlib rosbag tf + std_msgs cv_bridge dynamic_reconfigure @@ -33,9 +34,9 @@ pluginlib rosbag tf + std_msgs -