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
  Upstream should probably be updated to use modern cmake targets.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Apr 1, 2022
1 parent 0163c86 commit ebedf3c
Show file tree
Hide file tree
Showing 5 changed files with 9 additions and 6 deletions.
2 changes: 1 addition & 1 deletion tf2_eigen_kdl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,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 @@ -20,7 +20,8 @@ ament_python_install_package(${PROJECT_NAME}
add_library(${PROJECT_NAME} INTERFACE)
target_include_directories(${PROJECT_NAME} INTERFACE
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${orocos_kdl_INCLUDE_DIRS})
target_link_libraries(${PROJECT_NAME} INTERFACE
${geometry_msgs_TARGETS}
orocos-kdl
Expand Down
2 changes: 1 addition & 1 deletion tf2_geometry_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<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>

Expand Down
6 changes: 4 additions & 2 deletions tf2_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,8 @@ target_link_libraries(tf2_kdl INTERFACE
tf2_ros::tf2_ros)
target_include_directories(tf2_kdl INTERFACE
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
${orocos_kdl_INCLUDE_DIRS})

install(TARGETS tf2_kdl EXPORT export_tf2_kdl)

Expand Down Expand Up @@ -61,5 +62,6 @@ ament_export_include_directories("include/${PROJECT_NAME}")
# Export modern CMake targets
ament_export_targets(export_tf2_kdl)

ament_export_dependencies(builtin_interfaces geometry_msgs orocos_kdl tf2 tf2_ros)
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 ebedf3c

Please sign in to comment.