adam.parametric.model.parametric_factories package#
Submodules#
adam.parametric.model.parametric_factories.parametric_joint module#
- class adam.parametric.model.parametric_factories.parametric_joint.ParametricJoint(joint: Joint, math: SpatialMath, parent_link: ParametricLink, idx: int | None = None)[source]#
Bases:
Joint
Parametric Joint class
- modify(parent_joint_offset: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str])[source]#
- Parameters:
parent_joint_offset (npt.ArrayLike) – offset of the parent joint
- Returns:
the origin of the joint, parametric with respect to the parent link dimensions
- Return type:
npt.ArrayLike
- homogeneous(q: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str]) Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] [source]#
- Parameters:
q (npt.ArrayLike) – joint value
- Returns:
the homogenous transform of a joint, given q
- Return type:
npt.ArrayLike
- spatial_transform(q: Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str]) Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] [source]#
- Parameters:
q (npt.ArrayLike) – joint motion
- Returns:
spatial transform of the joint given q
- Return type:
npt.ArrayLike
adam.parametric.model.parametric_factories.parametric_link module#
- class adam.parametric.model.parametric_factories.parametric_link.Geometry(*values)[source]#
Bases:
Enum
The different types of geometries that constitute the URDF
- class adam.parametric.model.parametric_factories.parametric_link.Side(*values)[source]#
Bases:
Enum
The possible sides of a box geometry
- class adam.parametric.model.parametric_factories.parametric_link.ParametricLink(link: Link, math: SpatialMath, length_multiplier, densities)[source]#
Bases:
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() Buffer | _SupportsArray[dtype[Any]] | _NestedSequence[_SupportsArray[dtype[Any]]] | complex | bytes | str | _NestedSequence[complex | bytes | str] [source]#
- Returns:
- the 6x6 inertia matrix expressed at the
origin of the link (with rotation)
- Return type:
npt.ArrayLike
adam.parametric.model.parametric_factories.parametric_model module#
- class adam.parametric.model.parametric_factories.parametric_model.URDFParametricModelFactory(path: str, math: SpatialMath, links_name_list: list, length_multiplier, densities)[source]#
Bases:
ModelFactory
This factory generates robot elements from urdf_parser_py parametrized w.r.t. link lengths and densities
- Parameters:
ModelFactory – the Model factory
- build_joint(joint: Joint) Joint [source]#
- Parameters:
joint (Joint) – the urdf_parser_py joint
- Returns:
our joint representation
- Return type:
StdJoint/ParametricJoint