adam.parametric.model#
Submodules#
Classes#
Parametric Joint class |
|
Parametric Link class |
|
This factory generates robot elements from urdf_parser_py parametrized w.r.t. link lengths and densities |
Package Contents#
- class adam.parametric.model.ParametricJoint(joint: urdf_parser_py.urdf.Joint, math: adam.core.spatial_math.SpatialMath, parent_link: adam.parametric.model.parametric_factories.parametric_link.ParametricLink, idx: int | None = None)[source]#
Bases:
adam.model.Joint
Parametric Joint class
- math#
- name#
- parent#
- parent_parametric#
- child#
- type#
- axis#
- limit#
- idx = None#
Abstract base class for all joints.
- joint#
- offset#
- origin#
- modify(parent_joint_offset: numpy.typing.ArrayLike)[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: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
- Parameters:
q (npt.ArrayLike) – joint value
- Returns:
the homogenous transform of a joint, given q
- Return type:
npt.ArrayLike
- class adam.parametric.model.ParametricLink(link: urdf_parser_py.urdf.Link, math: adam.core.spatial_math.SpatialMath, length_multiplier, densities)[source]#
Bases:
adam.model.Link
Parametric Link class
- math#
- name#
- length_multiplier#
- densities#
- original_visual#
- visuals#
- original_density#
- link_offset#
- mass#
- inertial#
- 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
- class adam.parametric.model.URDFParametricModelFactory(path: str, math: adam.core.spatial_math.SpatialMath, links_name_list: list, length_multiplier, densities)[source]#
Bases:
adam.model.ModelFactory
This factory generates robot elements from urdf_parser_py parametrized w.r.t. link lengths and densities
- Parameters:
ModelFactory – the Model factory
- math#
- links_name_list#
- urdf_desc#
- name#
- length_multiplier#
- densities#
- get_joints() list[adam.model.Joint] [source]#
- Returns:
build the list of the joints
- Return type:
list[Joint]
- get_links() list[adam.model.Link] [source]#
- Returns:
build the list of the links
- Return type:
list[Link]
- get_frames() list[adam.model.StdLink] [source]#
- Returns:
build the list of the links
- Return type:
list[Link]
- build_joint(joint: urdf_parser_py.urdf.Joint) adam.model.Joint [source]#
- Parameters:
joint (Joint) – the urdf_parser_py joint
- Returns:
our joint representation
- Return type:
StdJoint/ParametricJoint
- build_link(link: urdf_parser_py.urdf.Link) adam.model.Link [source]#
- Parameters:
link (Link) – the urdf_parser_py link
- Returns:
our link representation
- Return type:
StdLink/ParametricLink