ikpy.link
module¶
This module implements the Link class.
-
class
ikpy.link.
Link
(name, length, bounds=None, is_final=False)[source]¶ Bases:
object
Base Link class.
Parameters: - name (string) – The name of the link
- bounds (tuple) – Optional : The bounds of the link. Defaults to None
-
get_rotation_axis
()[source]¶ Returns: coordinates of the rotation axis in the frame of the joint Return type: coords
-
get_link_frame_matrix
(actuator_parameters: dict)[source]¶ Return the frame matrix corresponding to the link, parameterized with theta
Parameters: actuator_parameters (dict) – Values for the actuator movements Note
Theta works for rotations, and for other one-dimensional actuators (ex: prismatic joints), even if the name can be misleading
-
class
ikpy.link.
URDFLink
(name: str, origin_translation: <MagicMock id='139836115923216'>, origin_orientation: <MagicMock id='139836115718096'>, rotation: Optional[<MagicMock id='139836115743568'>] = None, translation: Optional[<MagicMock id='139836115745296'>] = None, bounds=None, angle_representation='rpy', use_symbolic_matrix=True, joint_type: str = 'revolute')[source]¶ Bases:
ikpy.link.Link
Link in URDF representation.
Parameters: - name (str) – The name of the link
- bounds (tuple) – Optional : The bounds of the link. Defaults to None
- origin_translation (numpy.array) – The translation vector. (In URDF, attribute “xyz” of the “origin” element)
- origin_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 (str) – Optional : The representation used by the angle. Currently supported representations : rpy. Defaults to rpy, the URDF standard.
- use_symbolic_matrix (bool) – whether the transformation matrix is stored as a Numpy array or as a Sympy symbolic matrix.
- joint_type (str) – The URDF “type” attribute of the joint. Only support for revolute and prismatic joint for the moment
Returns: The link object
Return type: Example
URDFlink()
-
get_rotation_axis
()[source]¶ Returns: coordinates of the rotation axis in the frame of the joint Return type: coords
-
get_link_frame_matrix
(parameters)[source]¶ Return the frame matrix corresponding to the link, parameterized with theta
Parameters: actuator_parameters (dict) – Values for the actuator movements Note
Theta works for rotations, and for other one-dimensional actuators (ex: prismatic joints), even if the name can be misleading
-
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 (str) – 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) – whether 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
-
get_rotation_axis
()[source]¶ Returns: coordinates of the rotation axis in the frame of the joint Return type: coords
-
get_link_frame_matrix
(theta)[source]¶ Return the frame matrix corresponding to the link, parameterized with theta
Parameters: actuator_parameters (dict) – Values for the actuator movements Note
Theta works for rotations, and for other one-dimensional actuators (ex: prismatic joints), even if the name can be misleading
-