Skip to content

Commit c3cafef

Browse files
tf2_kdl: add python_orocos_kdl_vendor dependency (#745) (#748)
Signed-off-by: Ben Wolsieffer <[email protected]> (cherry picked from commit 894ab12) Co-authored-by: Ben Wolsieffer <[email protected]>
1 parent d262cff commit c3cafef

File tree

2 files changed

+1
-2
lines changed

2 files changed

+1
-2
lines changed

tf2_kdl/CMakeLists.txt

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,6 @@ install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
4444
if(BUILD_TESTING)
4545
find_package(ament_cmake_gtest REQUIRED)
4646
find_package(rclcpp REQUIRED)
47-
find_package(tf2_msgs REQUIRED)
4847

4948
ament_add_gtest(test_kdl test/test_tf2_kdl.cpp)
5049
target_link_libraries(test_kdl

tf2_kdl/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,11 +19,11 @@
1919
<depend>tf2</depend>
2020
<depend>tf2_ros</depend>
2121

22+
<exec_depend>python_orocos_kdl_vendor</exec_depend>
2223
<exec_depend>tf2_ros_py</exec_depend>
2324

2425
<test_depend>ament_cmake_gtest</test_depend>
2526
<test_depend>rclcpp</test_depend>
26-
<test_depend>tf2_msgs</test_depend>
2727

2828
<export>
2929
<build_type>ament_cmake</build_type>

0 commit comments

Comments
 (0)