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.
-
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.
-