Welcome to IKPy’s documentation!¶
Here you can find the documentation of the Inverse Kinematics API.
If you search getting started guides and tutorials, go to the Github repository.
ikpy
package¶
ikpy.chain
module¶
-
class
ikpy.chain.
Chain
(links, active_links=0, profile='', **kwargs)[source]¶ Bases:
object
The base Chain class
Parameters: -
forward_kinematics
(joints, full_kinematics=False)[source]¶ Returns the transformation matrix of the forward kinematics
Parameters: Returns: The transformation matrix
-
inverse_kinematic
(target, initial_position, first_active_joint=0, **kwargs)[source]¶ Computes the inverse kinematic on the specified target
Parameters: - target (numpy.array) – The target of the inverse kinematic, in meters
- initial_position (numpy.array) – the initial position of each joint of the chain
- first_active_joint (int) – The first active joint$
Returns: The list of the positions of each joint according to the target. Note : Inactive joints are in the list.
-
plot
(joints, ax, target=None, show=False)[source]¶ Plots the Chain using Matplotlib
Parameters: - joints (list) – The list of the positions of each joint
- ax (matplotlib.axes.Axes) – A matplotlib axes
- target (numpy.array) – An optional target
- show (bool) – Display the axe. Defaults to False
-
classmethod
from_urdf_file
(urdf_file, base_elements=['base_link'], last_link_vector=None, base_elements_type='joint')[source]¶ Creates a chain from an URDF file
Parameters: - urdf_file (string) – The path of the URDF file
- base_elements (list of strings) – List of the links beginning the chain
- last_link_vector (numpy.array) – Optional : The translation vector of the tip.
-
ikpy.link
module¶
-
class
ikpy.link.
URDFLink
(name, translation_vector, orientation, rotation, bounds=(None, None), angle_representation='rpy', use_symbolic_matrix=False)[source]¶ Bases:
ikpy.link.Link
Link in URDF representation.
Parameters: - name (string) – The name of the link
- bounds (tuple) – Optional : The bounds of the link. Defaults to None
- translation_vector (numpy.array) – The translation vector. (In URDF, attribute “xyz” of the “origin” element)
- orientation (numpy.array) – The orientation of the link. (In URDF, attribute “rpy” of the “origin” element)
- rotation (numpy.array) – The rotation axis of the link. (In URDF, attribute “xyz” of the “axis” element)
- angle_representation (string) – Optionnal : The representation used by the angle. Currently supported representations : rpy. Defaults to rpy, the URDF standard.
- use_symbolic_matrix (bool) – wether the transformation matrix is stored as a Numpy array or as a Sympy symbolic matrix.
Returns: The link object
Return type: Example: URDFlink()
-
class
ikpy.link.
DHLink
(name, d=0, a=0, bounds=None, use_symbolic_matrix=True)[source]¶ Bases:
ikpy.link.Link
Link in Denavit-Hartenberg representation.
Parameters: - name (string) – The name of the link
- bounds (tuple) – Optional : The bounds of the link. Defaults to None
- d (float) – offset along previous z to the common normal
- a (float) – offset along previous to the common normal
- use_symbolic_matrix (bool) – wether the transformation matrix is stored as Numpy array or as a Sympy symbolic matrix.
Returns: The link object
Return type:
-
class
ikpy.link.
OriginLink
[source]¶ Bases:
ikpy.link.Link
The link at the origin of the robot
ikpy.inverse_kinematics
module¶
ikpy.geometry_utils
module¶
-
ikpy.geometry_utils.
symbolic_Rz_matrix
(symbolic_theta)[source]¶ Matrice symbolique de rotation autour de l’axe Z
-
ikpy.geometry_utils.
rotation_matrix
(phi, theta, psi)[source]¶ Retourne la matrice de rotation décrite par les angles d’Euler donnés en paramètres
-
ikpy.geometry_utils.
symbolic_rotation_matrix
(phi, theta, symbolic_psi)[source]¶ Retourne une matrice de rotation où psi est symbolique
-
ikpy.geometry_utils.
rpy_matrix
(roll, pitch, yaw)[source]¶ Returns a rotation matrix described by the extrinsinc roll, pitch, yaw coordinates
-
ikpy.geometry_utils.
axis_rotation_matrix
(axis, theta)[source]¶ Returns a rotation matrix around the given axis
-
ikpy.geometry_utils.
symbolic_axis_rotation_matrix
(axis, symbolic_theta)[source]¶ Returns a rotation matrix around the given axis
-
ikpy.geometry_utils.
homogeneous_translation_matrix
(trans_x, trans_y, trans_z)[source]¶ Returns a translation matrix the homogeneous space
-
ikpy.geometry_utils.
from_transformation_matrix
(transformation_matrix)[source]¶ Converts a transformation matrix to a tuple (rotation_matrix, translation_vector)
-
ikpy.geometry_utils.
to_transformation_matrix
(rotation_matrix, translation)[source]¶ Converts a tuple (rotation_matrix, translation_vector) to a transformation matrix
-
ikpy.geometry_utils.
cartesian_to_homogeneous
(cartesian_matrix, matrix_type='numpy')[source]¶ Converts a cartesian matrix to an homogenous matrix
-
ikpy.geometry_utils.
cartesian_to_homogeneous_vectors
(cartesian_vector, matrix_type='numpy')[source]¶ Converts a cartesian vector to an homogenous vector
ikpy.URDF_utils
module¶
-
ikpy.URDF_utils.
find_next_joint
(root, current_link, next_joints)[source]¶ Find the next joint in the URDF tree
-
ikpy.URDF_utils.
find_next_link
(root, current_joint, next_links)[source]¶ Find the next link in the URDF tree
-
ikpy.URDF_utils.
get_urdf_parameters
(urdf_file, base_elements=['base_link'], last_link_vector=None, base_elements_type='joint')[source]¶ Returns translated parameters from the given URDF file
Parameters: - urdf_file (string) – The path of the URDF file
- base_elements (list of strings) – List of the links beginning the chain
- last_link_vector (numpy.array) – Optional : The translation vector of the tip.
-
ikpy.URDF_utils.
get_motor_parameters
(json_file)[source]¶ Returns a dictionnary with joints as keys, and a description (dict) of each joint as value
-
ikpy.URDF_utils.
convert_angle_to_pypot
(angle, joint, **kwargs)[source]¶ Converts an angle to a PyPot-compatible format