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