A module for generating the forward kinematics of a robot from a URDF. It can generate the forward kinematics represented as a dual quaternion or a transformation matrix. urdf2casadi
works both in python 2 and 3, and any platform that supports CasADi
and urdf_parser_py
.
With ROS:
- Get ROS (actually anything that installs
urdfdom_py
/urdf_parser_py
will do). - Get CasADi (e.g.
pip install casadi
). - Run
pip install --user .
in the folder.
Without ROS:
- Change the
urdfdom-py
tourdf-parser-py
inrequirements.txt
(line 3) and insetup.py
(line 20). - Get CasADi (e.g.
pip3 install casadi
). - Run
pip3 install --user .
in the folder (--user
specifies that it is a local install).
import casadi as cs
from urdf2casadi import converter
fk_dict = converter.from_file("root", "gantry_tool0", "robot_urdf_file_path.urdf")
print fk_dict.keys()
# should give ['q', 'upper', 'lower', 'dual_quaternion_fk', 'joint_names', 'T_fk', 'joint_list', 'quaternion_fk']
forward_kinematics = fk_dict["T_fk"]
print forward_kinematics([0.3, 0.3, 0.3, 0., 0.3, 0.7])
- Forward kinematics with SE(3) matrix
- Forward kinematics of rotation with quaternion
- Dual Quaternions as alternative to SE(3) matrices
- Dynamics from links and their inertia tags
- Denavit Hartenberg?
- unit tests
- Examples