ikpy.chain
module¶
This module implements the Chain class.
-
class
ikpy.chain.
Chain
(links, active_links_mask=None, name='chain', urdf_metadata=None, **kwargs)[source]¶ Bases:
object
The base Chain class
Parameters: - links (list[ikpy.link.Link]) – List of the links of the chain
- active_links_mask (list) – A list of boolean indicating that whether or not the corresponding link is active
- name (str) – The name of the Chain
- urdf_metadata – Technical attribute
-
forward_kinematics
(joints: List[T], full_kinematics=False)[source]¶ Returns the transformation matrix of the forward kinematics
Parameters: Returns: The transformation matrix
Return type: frame_matrix
-
inverse_kinematics
(target_position=None, target_orientation=None, orientation_mode=None, **kwargs)[source]¶ Parameters: - target_position (np.ndarray) – Vector of shape (3,): the target point
- target_orientation (np.ndarray) – Vector of shape (3,): the target orientation
- orientation_mode (str) – Orientation to target. Choices: * None: No orientation * “X”: Target the X axis * “Y”: Target the Y axis * “Z”: Target the Z axis * “all”: Target the entire frame (e.g. the three axes) (not currently supported)
- kwargs (See ikpy.inverse_kinematics.inverse_kinematic_optimization) –
Returns: The list of the positions of each joint according to the target. Note : Inactive joints are in the list.
Return type:
-
inverse_kinematics_frame
(target, initial_position=None, **kwargs)[source]¶ Computes the inverse kinematic on the specified target
Parameters: - target (numpy.array) – The frame target of the inverse kinematic, in meters. It must be 4x4 transformation matrix
- initial_position (numpy.array) – Optional : the initial position of each joint of the chain. Defaults to 0 for each joint
- kwargs (See ikpy.inverse_kinematics.inverse_kinematic_optimization) –
Returns: The list of the positions of each joint according to the target. Note : Inactive joints are in the list.
Return type:
-
classmethod
from_json_file
(json_file)[source]¶ Load a chain serialized in the JSON format. This is basically a URDF file with some metadata
Parameters: json_file (str) – Path to the json file serializing the robot
-
to_json_file
(force=False)[source]¶ Serialize the chain into a json that will be saved next to the original URDF, with the name of the chain
Parameters: force (bool) – Overwrite if existing Returns: Path of the exported JSON Return type: str
-
classmethod
from_urdf_file
(urdf_file, base_elements=None, last_link_vector=None, base_element_type='link', active_links_mask=None, name='chain', symbolic=True)[source]¶ Creates a chain from an URDF file
Parameters: - urdf_file (str) – 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.
- name (str) – The name of the Chain
- base_element_type (str) –
- active_links_mask (list[bool]) –
- symbolic (bool) – Use symbolic computations
Note
IKPY works with links, whereras URDF works with joints and links. The mapping is currently misleading:
- URDF joints = IKPY links
- URDF links are not used by IKPY. They are thrown away when parsing