Robotics Kinematics Library
Project description
pykin
Python Interface for the Robot Kinematics Library
This library has been created simply by referring to ikpy.
Features
- Pure python library
- Support only URDF file
- Compute Forward, Inverse Kinematics and Jacobian
- Compute Collision checkinkg
- Plot Robot Kinematic Chain
- Show Robot Mesh
Installation
Requirements
You need a python-fcl package to do object collision checking.
-
For Ubuntu, using
apt
sudo apt install liboctomap-dev
sudo apt install libfcl-dev
-
For Mac, First, Download the source and build it
-
octomap
git clone https://github.com/OctoMap/octomap.git
$ cd octomap $ mkdir build $ cd build $ cmake .. $ make $ make install
-
fcl
git clone https://github.com/flexible-collision-library/fcl.git
Since python-fcl uses version 0.5.0 of fcl, checkout with tag 0.5.0
$ cd fcl $ git checkout 0.5.0 $ mkdir build $ cd build $ cmake .. $ make $ make install
-
If the above installation is complete
pip install python-fcl
Install Pykin
pip install pykin
Quick Start
-
Robot Info
import pykin.robot from pykin.robot import Robot file_path = '../asset/urdf/baxter.urdf' robot = Robot(file_path) robot.show_robot_info() print(robot.joints) print(robot.links) print(robot.tree.root) print(robot.num_links) print(robot.num_active_joints) print(robot.get_active_joint_names)
-
Forward Kinematics
import sys import os import numpy as np from pprint import pprint from pykin import robot from pykin.robot import Robot from pykin.kinematics import transform as tf from pykin.utils import plot as plt file_path = '../asset/urdf/baxter.urdf' robot = Robot(file_path, tf.Transform(rot=[0.0, 0.0, 0.0], pos=[0, 0, 0])) # baxter_example head_thetas = [0.0] right_arm_thetas = [0, 0, 0, 0, 0, 0, 0] left_arm_thetas = [0, 0, 0, 0, 0, 0, 0] thetas = head_thetas + right_arm_thetas + left_arm_thetas fk = robot.forward_kinematics(thetas) """ If you want to know transformations of all links, you don't have to write get_desired_tree and desired_frame. """ pprint(fk) for link, T in fk.items(): print(f"link: {link}, pose:{np.concatenate((T.pos, T.rot))} ")
-
Inverse Kinematics
import sys import os import numpy as np from pprint import pprint from pykin import robot from pykin.robot import Robot from pykin.kinematics import transform as tf from pykin.utils import plot as plt file_path = '../asset/urdf/baxter.urdf' robot = Robot(file_path, tf.Transform(rot=[0.0, 0.0, 0.0], pos=[0, 0, 0])) # baxter_example head_thetas = [0.0] right_arm_thetas = [-np.pi/4, 0, 0, 0, 0, 0, 0] left_arm_thetas = [np.pi/4, 0, 0, 0, 0, 0, 0] init_right_thetas = [0, 0, 0, 0, 0, 0, 0] init_left_thetas = [0, 0, 0, 0, 0, 0, 0] robot.set_desired_tree("base", "right_wrist") right_arm_fk = robot.forward_kinematics(right_arm_thetas) target_r_pose = np.concatenate( (right_arm_fk["right_wrist"].pos, right_arm_fk["right_wrist"].rot)) ik_right_result = robot.inverse_kinematics( init_right_thetas, target_r_pose, method="numerical") robot.desired_frame = None thetas = head_thetas + ik_right_result + left_arm_thetas fk = robot.forward_kinematics(thetas) _, ax = plt.init_3d_figure() plt.plot_robot(robot, fk, ax, "baxter") ax.legend() plt.show_figure()
-
Result
Inverse Kinematics
You can see an example of IK by running the command below.
$ cd pykin/tests
$ python robot_ik_baxter_test.py
-
Forward Kinematics
-
IK Newton Raphson method
-
IK Levenberg-Marquardt method
It can be seen that the LM method is faster and more accurate than the NR method when using IK.
Project details
Release history Release notifications | RSS feed
Download files
Download the file for your platform. If you're not sure which to choose, learn more about installing packages.