Skip to content

Commit

Permalink
Use ament_target_dependencies to ensure correct dependency order (#156)
Browse files Browse the repository at this point in the history
* Use ament_target_dependencies to ensure correct dependency order

Resolves compilation issues when building in an overlayed workspace.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>

* Explicitly add dependencies for executable targets
  • Loading branch information
jacobperron authored Aug 27, 2019
1 parent f282d27 commit 4e7fba9
Showing 1 changed file with 29 additions and 35 deletions.
64 changes: 29 additions & 35 deletions tf2_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,13 +23,7 @@ find_package(rclcpp REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_msgs REQUIRED)

include_directories(include
${geometry_msgs_INCLUDE_DIRS}
${message_filters_INCLUDE_DIRS}
${rclcpp_INCLUDE_DIRS}
${tf2_INCLUDE_DIRS}
${tf2_msgs_INCLUDE_DIRS}
)
include_directories(include)

# tf2_ros library
add_library(${PROJECT_NAME} SHARED
Expand All @@ -42,13 +36,13 @@ add_library(${PROJECT_NAME} SHARED
src/static_transform_broadcaster.cpp
)

target_link_libraries(${PROJECT_NAME}
${geometry_msgs_LIBRARIES}
${message_filters_LIBRARIES}
${rclcpp_LIBRARIES}
${tf2_LIBRARIES}
${tf2_msgs_LIBRARIES}
)
ament_target_dependencies(${PROJECT_NAME}
"geometry_msgs"
"message_filters"
"rclcpp"
"tf2"
"tf2_msgs"
)

target_compile_definitions(${PROJECT_NAME} PRIVATE "TF2_ROS_BUILDING_DLL")

Expand All @@ -69,33 +63,33 @@ add_executable(static_transform_publisher
)
target_link_libraries(static_transform_publisher
${PROJECT_NAME}
${geometry_msgs_LIBRARIES}
${rclcpp_LIBRARIES}
${tf2_LIBRARIES}
${tf2_msgs_LIBRARIES}
)
)
ament_target_dependencies(static_transform_publisher
"geometry_msgs"
"rclcpp"
"tf2_msgs"
)

add_executable(tf2_echo
src/tf2_echo.cpp
)
target_link_libraries(tf2_echo
${PROJECT_NAME}
${geometry_msgs_LIBRARIES}
${rclcpp_LIBRARIES}
${tf2_LIBRARIES}
${tf2_msgs_LIBRARIES}
)

add_executable(tf2_monitor
src/tf2_monitor.cpp
)
target_link_libraries(tf2_monitor
${PROJECT_NAME}
${geometry_msgs_LIBRARIES}
${rclcpp_LIBRARIES}
${tf2_LIBRARIES}
${tf2_msgs_LIBRARIES}
)
)
ament_target_dependencies(tf2_echo
"rclcpp"
)

add_executable(tf2_monitor
src/tf2_monitor.cpp
)
target_link_libraries(tf2_monitor
${PROJECT_NAME}
)
ament_target_dependencies(tf2_monitor
"rclcpp"
"tf2_msgs"
)

# Install rules
install(TARGETS
Expand Down

0 comments on commit 4e7fba9

Please sign in to comment.