ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

ros generate checking headers before generating message headers

asked 2017-02-16 21:12:41 -0500

errolflynn gravatar image

I am generating a message in this package. Then using that message in a header file in the same package. This builds on my system, but not on others (see TravisCI build failures). It seems that cmake/catkin is searching for the header file to be generated before it is generated.

Not sure why this builds for me but not for others. Possibly there is some cached header file in the build directory that my preprocessor is able to reference. Anyways, what is wrong here?

CMakeLists.txt for the project shown below.

cmake_minimum_required(VERSION 2.8.3)
project(terpcopter_common)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
  message_generation
  std_msgs
)

## Generate messages in the 'msg' folder
add_message_files(
  FILES
  Health.msg
)

## Generate added messages and services with any dependencies listed here
generate_messages(
  DEPENDENCIES
  std_msgs  # Or other packages containing msgs
  terpcopter_common
)

catkin_package(
  INCLUDE_DIRS include
  LIBRARIES terpcopter_common
  CATKIN_DEPENDS message_runtime
#  DEPENDS system_lib
)

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(include)

## Declare a C++ library
add_library(terpcopter_common
  src/${PROJECT_NAME}/system.cpp
  src/${PROJECT_NAME}/tc_node.cpp
  src/${PROJECT_NAME}/tc_manager_node.cpp
)
## Mark cpp header files for installation
install(DIRECTORY include/${PROJECT_NAME}/
  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
  FILES_MATCHING PATTERN "*.h"
  PATTERN ".svn" EXCLUDE
)

image description

image description

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2017-02-16 21:36:12 -0500

William gravatar image

You're missing a dependency between your library and the cmake target that generates the message files (which are aggregated with ${PROJECT_NAME}_EXPORTED_TARGETS), see the last couple of paragraphs here:

http://docs.ros.org/indigo/api/catkin...

P.S. please don't post images of text, it's impossible to search.

edit flag offensive delete link more

Comments

please don't post images of text, it's impossible to search.

+many on that. Don't understand why that is suddenly such a 'thing'.

gvdhoorn gravatar image gvdhoorn  ( 2017-02-17 11:29:41 -0500 )edit

it's from travis.ci. Didn't look for the actual printout. Will do so in the future. Thanks

errolflynn gravatar image errolflynn  ( 2017-02-25 20:00:43 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2017-02-16 21:12:41 -0500

Seen: 1,428 times

Last updated: Feb 16 '17