Skip to content

Commit

Permalink
Cleanup the package.xml and CMakeLists.txt
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette committed May 9, 2019
1 parent ae5652d commit ec63e8b
Show file tree
Hide file tree
Showing 2 changed files with 27 additions and 43 deletions.
52 changes: 18 additions & 34 deletions tf2_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,61 +11,45 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(orocos_kdl REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(rclcpp REQUIRED)

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

link_directories(${orocos_kdl_LIBRARY_DIRS})
include_directories(include ${rclpy_INCLUDE_DIRS}
${rmw_implementation_INCLUDE_DIRS}
${std_msgs_INCLUDE_DIRS}
${Eigen3_INCLUDE_DIRS}
${GTEST_INCLUDE_DIRS})
# TODO(clalancette): Port python once https://github.com/ros2/geometry2/pull/99 is merged
# ament_python_install_package(${PROJECT_NAME}
# PACKAGE_DIR src/${PROJECT_NAME})

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION include/${PROJECT_NAME}
)

install(PROGRAMS scripts/test.py
DESTINATION lib/${PROJECT_NAME}
)
# TODO(clalancette): Port python tests once https://github.com/ros2/geometry/pull/99 is merged
# install(PROGRAMS scripts/test.py
# DESTINATION lib/${PROJECT_NAME}
# )


if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package (Threads)
find_package(Eigen3 REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(rclcpp REQUIRED)
find_package(tf2_msgs REQUIRED)

ament_add_gtest(test_kdl test/test_tf2_kdl.cpp)
target_include_directories(test_kdl PUBLIC
include
${tf2_INCLUDE_DIRS}
${tf2_ros_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${rclcpp_INCLUDE_DIRS}
${orocos_kdl_INCLUDE_DIRS}
include
)

target_link_libraries(test_kdl ${rclpy_LIBRARIES}
${rclcpp_LIBRARIES}
${rmw_implementation_LIBRARIES}
${GTEST_LIBRARIES}
${orocos_kdl_LIBRARIES}
${CMAKE_THREAD_LIBS_INIT})

ament_target_dependencies(test_kdl
builtin_interfaces
orocos_kdl
rclcpp
tf2
tf2_ros
tf2_msgs)
endif()

ament_export_include_directories(include ${Eigen3_INCLUDE_DIRS})
ament_export_dependencies(Eigen3 orocos_kdl)
ament_export_include_directories(include)
ament_export_dependencies(builtin_interfaces Eigen3 geometry_msgs orocos_kdl tf2 tf2_ros)
ament_package()
18 changes: 9 additions & 9 deletions tf2_kdl/package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
<package>
<package format="2">
<name>tf2_kdl</name>
<version>0.9.1</version>
<description>
Expand All @@ -12,16 +12,16 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>eigen</build_depend> <!-- needed by kdl interally -->
<build_depend>orocos_kdl</build_depend>
<build_depend>tf2</build_depend>
<build_depend>tf2_ros</build_depend>
<depend>builtin_interfaces</depend>
<depend>eigen</depend> <!-- needed by kdl interally -->
<depend>geometry_msgs</depend>
<depend>orocos_kdl</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>

<run_depend>eigen</run_depend>
<run_depend>orocos_kdl</run_depend>
<run_depend>tf2</run_depend>
<run_depend>tf2_ros</run_depend>
<test_depend>ament_cmake_gtest</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>tf2_msgs</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down

0 comments on commit ec63e8b

Please sign in to comment.