adam.parametric.model.parametric_factories.parametric_link#
Classes#
The different types of geometries that constitute the URDF |
|
The possible sides of a box geometry |
|
Parametric Link class |
Module Contents#
- class adam.parametric.model.parametric_factories.parametric_link.Geometry(*args, **kwds)[source]#
Bases:
enum.Enum
The different types of geometries that constitute the URDF
- class adam.parametric.model.parametric_factories.parametric_link.Side(*args, **kwds)[source]#
Bases:
enum.Enum
The possible sides of a box geometry
- class adam.parametric.model.parametric_factories.parametric_link.ParametricLink(link: urdf_parser_py.urdf.Link, math: adam.core.spatial_math.SpatialMath, length_multiplier, densities)[source]#
Bases:
adam.model.Link
Parametric Link class
- get_principal_length()[source]#
Method computing the principal link length, i.e. the dimension in which the kinematic chain grows
- get_principal_length_parametric()[source]#
Method computing the principal link length parametric, i.e. the dimension in which the kinematic chain grows
- compute_joint_offset(joint_i, parent_offset)[source]#
- Returns:
the child joint offset
- Return type:
npt.ArrayLike
- static get_geometry(visual_obj)[source]#
- Returns:
the geometry of the link and the related urdf object
- Return type:
(Geometry, urdf geometry)
- compute_volume(length_multiplier)[source]#
- Returns:
the volume and the dimension parametric
- Return type:
(npt.ArrayLike, npt.ArrayLike)
- compute_mass()[source]#
Function that computes the mass starting from the densities, and the link volume :returns: the link mass :rtype: (npt.ArrayLike)
- compute_inertia_parametric()[source]#
- Returns:
inertia (ixx, iyy and izz) with the formula that corresponds to the geometry
- Return type:
Inertia Parametric
Formulas retrieved from https://en.wikipedia.org/wiki/List_of_moments_of_inertia
- spatial_inertia() numpy.typing.ArrayLike [source]#
- Returns:
- the 6x6 inertia matrix expressed at the
origin of the link (with rotation)
- Return type:
npt.ArrayLike