Skip to content

Commit

Permalink
Depend on orocos_kdl_vendor
Browse files Browse the repository at this point in the history
* Change package.xml dependency to the vendor package
* Add missing include directories for orocos_kdl
* Install tf2_kdl as a header-only target

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Feb 24, 2022
1 parent 5a298f9 commit 6df4941
Show file tree
Hide file tree
Showing 5 changed files with 33 additions and 16 deletions.
2 changes: 1 addition & 1 deletion tf2_eigen_kdl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
<build_depend>eigen</build_depend>
<build_export_depend>eigen</build_export_depend>

<depend>orocos_kdl</depend>
<depend>orocos_kdl_vendor</depend>
<depend>tf2</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
3 changes: 2 additions & 1 deletion tf2_geometry_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@ find_package(tf2_ros REQUIRED)
add_library(${PROJECT_NAME} INTERFACE)
target_include_directories(${PROJECT_NAME} INTERFACE
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include>")
"$<INSTALL_INTERFACE:include>"
${orocos_kdl_INCLUDE_DIRS})
target_link_libraries(${PROJECT_NAME} INTERFACE
${geometry_msgs_TARGETS}
orocos-kdl
Expand Down
6 changes: 2 additions & 4 deletions tf2_geometry_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,14 +14,12 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>geometry_msgs</depend>
<depend>orocos_kdl</depend>
<depend>orocos_kdl_vendor</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>

<!-- python support not yet ported
<build_depend>python_orocos_kdl</build_depend>
<exec_depend>python_orocos_kdl</exec_depend>
<depend>python_orocos_kdl_vendor</depend>
-->

<exec_depend>tf2_ros_py</exec_depend>
Expand Down
36 changes: 27 additions & 9 deletions tf2_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,27 @@ find_package(orocos_kdl REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)

add_library(${PROJECT_NAME} INTERFACE)
target_include_directories(${PROJECT_NAME} INTERFACE
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${orocos_kdl_INCLUDE_DIRS}
)
target_link_libraries(${PROJECT_NAME} INTERFACE
orocos-kdl
)
ament_target_dependencies(${PROJECT_NAME} INTERFACE
builtin_interfaces
geometry_msgs
tf2
tf2_ros
)

install(
TARGETS ${PROJECT_NAME}
EXPORT export_${PROJECT_NAME}
)

ament_python_install_package(${PROJECT_NAME}
PACKAGE_DIR src/${PROJECT_NAME})

Expand All @@ -35,18 +56,15 @@ if(BUILD_TESTING)
find_package(tf2_msgs REQUIRED)

ament_add_gtest(test_kdl test/test_tf2_kdl.cpp)
target_include_directories(test_kdl PUBLIC
include
target_link_libraries(test_kdl
${PROJECT_NAME}
)
ament_target_dependencies(test_kdl
builtin_interfaces
orocos_kdl
rclcpp
tf2
tf2_ros
tf2_msgs)
tf2_msgs
)
endif()

ament_export_include_directories(include)
ament_export_dependencies(builtin_interfaces geometry_msgs orocos_kdl tf2 tf2_ros)
ament_export_targets(export_${PROJECT_NAME})
ament_export_dependencies(builtin_interfaces geometry_msgs orocos_kdl_vendor tf2 tf2_ros)
ament_package()
2 changes: 1 addition & 1 deletion tf2_kdl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@

<depend>builtin_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>orocos_kdl</depend>
<depend>orocos_kdl_vendor</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>

Expand Down

0 comments on commit 6df4941

Please sign in to comment.