Skip to content

Commit

Permalink
Fix hard-coded Windows paths.
Browse files Browse the repository at this point in the history
These come about because of the use of the old-style CMake
variables like ${orocos_kdl_INCLUDE_DIRS}.  Unfortunately,
there is a bug in the orocos_kdl CMake modern targets where
they forget to export a dependency on Eigen.  To workaround
this, make an explicit dependency on Eigen (even though we
don't directly use it), and use the Eigen targets instead.

Note that on Windows, this *still* causes us to use a
hardcoded path on Eigen.  However, this path is less problematic
because it will always be there if the user followed our
installation instructions (and won't be a "random" path like
C:\ci\ws\install\include).  Also, once we fix
ros2/choco-packages#19 , this hard-coded
path will go away as well.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
  • Loading branch information
clalancette committed Apr 29, 2022
1 parent 122fb39 commit a030eec
Show file tree
Hide file tree
Showing 2 changed files with 34 additions and 4 deletions.
19 changes: 17 additions & 2 deletions tf2_geometry_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,16 @@ if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug")
endif()
find_package(Python3 REQUIRED COMPONENTS Interpreter Development)

# TODO(clalancette): This package doesn't directly depend on Eigen, but orocos-kdl
# fails to properly export the dependency. One possible solution would be to add
# ${orocos_kdl_INCLUDE_DIRS} to the include directories, but that unfortunately causes
# hard-coded paths to show up in Windows packaging builds. Instead, depend on Eigen3
# here to fix the missing export
find_package(Eigen3 QUIET NO_MODULE)
# Work around broken find module in AlmaLinux/RHEL eigen3-devel from PowerTools repo
if(NOT Eigen3_FOUND)
find_package(Eigen3 REQUIRED)
endif()
find_package(geometry_msgs REQUIRED)
find_package(orocos_kdl REQUIRED)
find_package(tf2 REQUIRED)
Expand All @@ -29,13 +39,18 @@ 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}>"
${orocos_kdl_INCLUDE_DIRS})
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
target_link_libraries(${PROJECT_NAME} INTERFACE
${geometry_msgs_TARGETS}
orocos-kdl
tf2::tf2
tf2_ros::tf2_ros)
if(TARGET Eigen3::Eigen)
# TODO(sloretz) require target to exist when https://github.com/ros2/choco-packages/issues/19 is addressed
target_link_libraries(${PROJECT_NAME} INTERFACE Eigen3::Eigen)
else()
target_include_directories(${PROJECT_NAME} INTERFACE ${Eigen3_INCLUDE_DIRS})
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
19 changes: 17 additions & 2 deletions tf2_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,16 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
# TODO(clalancette): This package doesn't directly depend on Eigen, but orocos-kdl
# fails to properly export the dependency. One possible solution would be to add
# ${orocos_kdl_INCLUDE_DIRS} to the include directories, but that unfortunately causes
# hard-coded paths to show up in Windows packaging builds. Instead, depend on Eigen3
# here to fix the missing export
find_package(Eigen3 QUIET NO_MODULE)
# Work around broken find module in AlmaLinux/RHEL eigen3-devel from PowerTools repo
if(NOT Eigen3_FOUND)
find_package(Eigen3 REQUIRED)
endif()
find_package(geometry_msgs REQUIRED)
find_package(orocos_kdl REQUIRED)
find_package(tf2 REQUIRED)
Expand All @@ -29,8 +39,13 @@ 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}>"
${orocos_kdl_INCLUDE_DIRS})
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
if(TARGET Eigen3::Eigen)
# TODO(sloretz) require target to exist when https://github.com/ros2/choco-packages/issues/19 is addressed
target_link_libraries(tf2_kdl INTERFACE Eigen3::Eigen)
else()
target_include_directories(tf2_kdl INTERFACE ${Eigen3_INCLUDE_DIRS})
endif()

install(TARGETS tf2_kdl EXPORT export_tf2_kdl)

Expand Down

0 comments on commit a030eec

Please sign in to comment.