Skip to content

Commit

Permalink
Use THIS_PACKAGE_INCLUDE_DEPENDS list
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <tyler@picknik.ai>
  • Loading branch information
tylerjw committed Jan 26, 2023
1 parent 8dc3417 commit a781424
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 30 deletions.
25 changes: 13 additions & 12 deletions kinematics_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,17 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Eigen3
rclcpp
rclcpp_lifecycle
)

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

# Create interface library for kinematics base class
add_library(kinematics_interface INTERFACE)
Expand All @@ -17,10 +24,8 @@ target_include_directories(kinematics_interface INTERFACE
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/kinematics_interface>
)
target_link_libraries(kinematics_interface INTERFACE
Eigen3::Eigen
rclcpp::rclcpp
rclcpp_lifecycle::rclcpp_lifecycle
ament_target_dependencies(kinematics_interface INTERFACE
${THIS_PACKAGE_INCLUDE_DEPENDS}
)

# Causes the visibility macros to use dllexport rather than dllimport,
Expand All @@ -40,9 +45,5 @@ install(
)

ament_export_targets(export_kinematics_interface HAS_LIBRARY_TARGET)
ament_export_dependencies(
Eigen3
rclcpp
rclcpp_lifecycle
)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()
33 changes: 15 additions & 18 deletions kinematics_interface_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,19 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
Eigen3
kdl_parser
kinematics_interface
pluginlib
tf2_eigen_kdl
)

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(kdl_parser REQUIRED)
find_package(kinematics_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(tf2_eigen_kdl REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()

add_library(
kinematics_interface_kdl
Expand All @@ -22,12 +29,8 @@ target_include_directories(kinematics_interface_kdl PUBLIC
$<INSTALL_INTERFACE:include/kinematics_interface_kdl>
)
target_compile_features(kinematics_interface_kdl PUBLIC cxx_std_17)
target_link_libraries(kinematics_interface_kdl PUBLIC
Eigen3::Eigen
kdl_parser::kdl_parser
kinematics_interface::kinematics_interface
pluginlib::pluginlib
tf2_eigen_kdl::tf2_eigen_kdl
ament_target_dependencies(kinematics_interface_kdl PUBLIC
${THIS_PACKAGE_INCLUDE_DEPENDS}
)

pluginlib_export_plugin_description_file(kinematics_interface kinematics_interface_kdl.xml)
Expand Down Expand Up @@ -60,11 +63,5 @@ install(
)

ament_export_targets(export_kinematics_interface_kdl HAS_LIBRARY_TARGET)
ament_export_dependencies(
Eigen3
kdl_parser
kinematics_interface
pluginlib
tf2_eigen_kdl
)
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS})
ament_package()

0 comments on commit a781424

Please sign in to comment.