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:
  • links (list) – List of the links of the chain
  • active_links (list) – The list of the positions of the active links
forward_kinematics(joints, full_kinematics=False)[source]

Returns the transformation matrix of the forward kinematics

Parameters:
  • joints (list) – The list of the positions of each joint. Note : Inactive joints must be in the list.
  • full_kinematics (bool) – Return the transorfmation matrixes of each joint
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.chain.pinv()[source]

ikpy.inverse_kinematics module

ikpy.inverse_kinematics.inverse_kinematic_optimization(chain, target, starting_nodes_angles, bounds=None, first_active_joint=0, regularization_parameter=None, max_iter=None, **kwargs)[source]

Computes the inverse kinematic on the specified target with an optimization method

ikpy.geometry_utils module

ikpy.geometry_utils.Rx_matrix(theta)[source]

Rotation matrix around the X axis

ikpy.geometry_utils.Rz_matrix(theta)[source]

Rotation matrix around the Z axis

ikpy.geometry_utils.symbolic_Rz_matrix(symbolic_theta)[source]

Matrice symbolique de rotation autour de l’axe Z

ikpy.geometry_utils.Ry_matrix(theta)[source]

Rotation matrix around the Y axis

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.geometry_utils.homogeneous_to_cartesian_vectors(homogeneous_vector)[source]

Converts a cartesian vector to an homogenous vector

ikpy.geometry_utils.homogeneous_to_cartesian(homogeneous_matrix)[source]

Converts a cartesian vector to an homogenous matrix

ikpy.URDF_utils module

ikpy.URDF_utils.find_next_joint(root, current_link, next_joints)[source]

Find the next joint in the URDF tree

Find the next link in the URDF tree

ikpy.URDF_utils.get_chain_from_joints(urdf_file, joints)[source]
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

ikpy.URDF_utils.convert_angle_from_pypot(angle, joint, **kwargs)[source]

Converts an angle to a PyPot-compatible format

ikpy.URDF_utils.convert_angle_limit(angle, joint, **kwargs)[source]

Converts the limit angle of the PyPot JSON file to the internal format

Indices and tables