Supported Joint Types:
- Fixed
- Revolute
- Continuous
- Prismatic
- Floating - 6-DoF joint (not coverd by unit tests)
- Planar (not coverd by unit tests)
$ pip install dlkinematics
import tensorflow as tf
from dlkinematics.urdf import chain_from_urdf_file
from dlkinematics.dlkinematics import DLKinematics
# Load URDF
chain = chain_from_urdf_file('data/human.urdf')
# Create DLKinematics
dlkinematics = DLKinematics(
chain,
base_link="human_base",
end_link="human_spine_2",
batch_size=2)
# Joint configuartion
thetas = tf.Variable([1., 2., 3., 4.], dtype=tf.float32)
# Forward pass
with tf.GradientTape() as tape:
result = dlkinematics.forward(thetas)
print(result)
print(tape.gradient(result, thetas))
from dlkinematics.training_utils import ForwardKinematics
from tensorflow import keras
import tensorflow as tf
model = keras.Sequential()
FK_layer = ForwardKinematics(
urdf_file = 'path/to/urdf',
base_link = 'link0',
end_link = 'linkN',
batch_size = 2)
model.add(FK_layer)
# Output shape of FK_layer is (batch_size, 4, 4)
The tests use ROS packages to validate the result of the dlkinematics module.
-
Build the docker image for tests:
$ docker build -t dlkinematics_tests .
-
Start the container in the root folder of the project:
$ docker run -it -v $PWD:/work dlkinematics_tests python3 -m pytest
-
Execute all tests:
$ docker run -it -v $PWD:/work dlkinematics_tests python3 -m pytest
Execute only a single testfile:
$ docker run -it -v $PWD:/work dlkinematics_tests python3 -m pytest tests/test_prismatic.py