First, you need to install IKPy (see installations instructions).
You also need a URDF file.
By default, we use the files provided in the resources folder of the IKPy repo.
Import the IKPy module :
In [1]:
import ikpy
import numpy as np
from ikpy import plot_utils
The basic element of IKPy is the kinematic Chain
.
To create a chain from an URDF file :
In [2]:
my_chain = ikpy.chain.Chain.from_urdf_file("../resources/poppy_ergo.URDF")
Note : as mentioned before, here we use a file in the resource folder.
In Inverse Kinematics, you want your kinematic chain to reach a 3D position in space.
To have a more general representation of position, IKPy works with homogeneous coordinates. It is a 4x4 matrix storing both position and orientation. Prepare your desired position as a 4x4 matrix. Here we only consider position, not orientation of the chain.
In [4]:
target_vector = [ 0.1, -0.2, 0.1]
target_frame = np.eye(4)
target_frame[:3, 3] = target_vector
In [4]:
print("The angles of each joints are : ", my_chain.inverse_kinematics(target_frame))
You can check that the Inverse Kinematics is correct by comparing with the original position vector :
In [5]:
real_frame = my_chain.forward_kinematics(my_chain.inverse_kinematics(target_frame))
print("Computed position vector : %s, original position vector : %s" % (real_frame[:3, 3], target_frame[:3, 3]))
(If the code below doesn't work, comment the %maplotlib notebook
line, and uncomment the %matplotlib inline
line)
In [7]:
# If there is a matplotlib error, uncomment the next line, and comment the line below it.
# %matplotlib inline
%matplotlib notebook
import matplotlib.pyplot as plt
ax = plot_utils.init_3d_figure()
my_chain.plot(my_chain.inverse_kinematics(target_frame), ax, target=target_vector)
plt.xlim(-0.1, 0.1)
plt.ylim(-0.1, 0.1)
Out[7]:
You're done! Go to the tutorials to understand the general concepts of the library.