Skip to content

Commit

Permalink
Spliting tf2_kdl
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <[email protected]>

Removing extra dependencies

Signed-off-by: CursedRock17 <[email protected]>

Updating package version

Signed-off-by: CursedRock17 <[email protected]>

Correcting dependencies

Signed-off-by: CursedRock17 <[email protected]>

Fixing imports

Signed-off-by: CursedRock17 <[email protected]>

Removing excess from tf2_kdl

Signed-off-by: CursedRock17 <[email protected]>

Fixing imports

Signed-off-by: CursedRock17 <[email protected]>

Removing excess from tf2_kdl

Signed-off-by: CursedRock17 <[email protected]>
  • Loading branch information
CursedRock17 committed Apr 4, 2024
1 parent 8752526 commit e944dfd
Show file tree
Hide file tree
Showing 12 changed files with 55 additions and 15 deletions.
2 changes: 2 additions & 0 deletions geometry2/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,9 +27,11 @@
<exec_depend>tf2_eigen_kdl</exec_depend>
<exec_depend>tf2_geometry_msgs</exec_depend>
<exec_depend>tf2_kdl</exec_depend>
<exec_depend>tf2_kdl_py</exec_depend>
<exec_depend>tf2_msgs</exec_depend>
<exec_depend>tf2_py</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>
<exec_depend>tf2_sensor_msgs</exec_depend>
<exec_depend>tf2_tools</exec_depend>

Expand Down
8 changes: 0 additions & 8 deletions tf2_kdl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,6 @@ find_package(orocos_kdl REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)

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

add_library(tf2_kdl INTERFACE)
target_link_libraries(tf2_kdl INTERFACE
${builtin_interfaces_TARGETS}
Expand All @@ -37,11 +34,6 @@ install(TARGETS tf2_kdl EXPORT export_tf2_kdl)

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

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

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(rclcpp REQUIRED)
Expand Down
2 changes: 0 additions & 2 deletions tf2_kdl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,6 @@
<depend>tf2</depend>
<depend>tf2_ros</depend>

<exec_depend>tf2_ros_py</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>rclcpp</test_depend>
<test_depend>tf2_msgs</test_depend>
Expand Down
3 changes: 0 additions & 3 deletions tf2_kdl/test/test_python.launch

This file was deleted.

3 changes: 3 additions & 0 deletions tf2_kdl_py/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package tf2_kdl_py
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
25 changes: 25 additions & 0 deletions tf2_kdl_py/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<package format="2">
<name>tf2_kdl_py</name>
<version>0.36.1</version>
<description>
PyKDL binding for tf2
</description>

<maintainer email="[email protected]">Alejandro Hernandez Cordero</maintainer>
<maintainer email="[email protected]">Chris Lalancette</maintainer>

<license>Apache-2.0</license>

<exec_depend>geometry_msgs</exec_depend>
<exec_depend>python_orocos_kdl_vendor</exec_depend>
<exec_depend>tf2_ros_py</exec_depend>

<test_depend>builtin_interfaces</test_depend>
<test_depend>python3-pytest</test_depend>
<test_depend>rclpy</test_depend>

<export>
<build_type>ament_python</build_type>
</export>

</package>
Empty file added tf2_kdl_py/resource/tf2_kdl_py
Empty file.
4 changes: 4 additions & 0 deletions tf2_kdl_py/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/tf2_kdl_py
[install]
install_scripts=$base/lib/tf2_kdl_py
21 changes: 21 additions & 0 deletions tf2_kdl_py/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
from setuptools import find_packages, setup

package_name = 'tf2_kdl_py'

setup(
name=package_name,
version='0.36.1',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='Alejandro Hernandez Cordero, Chris Lalancette',
maintainer_email='[email protected], [email protected]',
description='PyKDL binding for tf2',
license='Apache-2.0',
tests_require=['pytest'],
)
2 changes: 0 additions & 2 deletions tf2_kdl/scripts/test.py → tf2_kdl_py/test/test_kdl.py
100755 → 100644
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
#!/usr/bin/python

# Copyright 2008 Willow Garage, Inc.
#
# Redistribution and use in source and binary forms, with or without
Expand Down
File renamed without changes.
File renamed without changes.

0 comments on commit e944dfd

Please sign in to comment.