adam.model#
Submodules#
Classes#
Inertial description |
|
Base Joint class. You need to fill at least these fields |
|
Base Link class. You need to fill at least these fields |
|
The abstract class of the model factory. |
|
Pose class |
|
Model class. It describes the robot using links and frames and their connectivity |
|
Standard Joint class |
|
Standard Link class |
|
This factory generates robot elements from urdf_parser_py |
|
The node class |
|
The directed tree class |
Package Contents#
- class adam.model.Joint[source]#
Bases:
abc.ABC
Base Joint class. You need to fill at least these fields
- name: str#
- parent: str#
- child: str#
- type: str#
- axis: list#
- idx: int#
Abstract base class for all joints.
- abstractmethod spatial_transform(q: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
- Parameters:
q (npt.ArrayLike) – joint motion
- Returns:
spatial transform of the joint given q
- Return type:
npt.ArrayLike
- class adam.model.Link[source]#
Bases:
abc.ABC
Base Link class. You need to fill at least these fields
- name: str#
- visuals: list#
- collisions: list#
- class adam.model.ModelFactory[source]#
Bases:
abc.ABC
The abstract class of the model factory.
The model factory is responsible for creating the model.
You need to implement all the methods in your concrete implementation
- name: str#
- abstractmethod get_links() list[Link] [source]#
- Returns:
the list of the link
- Return type:
list[Link]
- class adam.model.Model[source]#
Model class. It describes the robot using links and frames and their connectivity
- name: str#
- links: dict[str, adam.model.abc_factories.Link]#
- frames: dict[str, adam.model.abc_factories.Link]#
- joints: dict[str, adam.model.abc_factories.Joint]#
- tree: adam.model.tree.Tree#
- NDoF: int#
- actuated_joints: list[str]#
- property N: int#
Returns: int: the number of links in the model
- static build(factory: adam.model.abc_factories.ModelFactory, joints_name_list: list[str] = None) Model [source]#
generates the model starting from the list of joints and the links-joints factory
- Parameters:
factory (ModelFactory) – the factory that generates the links and the joints, starting from a description (eg. urdf)
joints_name_list (list[str]) – the list of the actuated joints
- Returns:
the model describing the robot
- Return type:
- get_joints_chain(root: str, target: str) list[adam.model.abc_factories.Joint] [source]#
generate the joints chains from a link to a link
- Parameters:
root (str) – the starting link
target (str) – the target link
- Returns:
the list of the joints
- Return type:
list[Joint]
- class adam.model.StdJoint(joint: urdf_parser_py.urdf.Joint, math: adam.core.spatial_math.SpatialMath, idx: int | None = None)[source]#
Bases:
adam.model.Joint
Standard Joint class
- math#
- name#
- parent#
- child#
- type#
- axis#
- origin#
- limit#
- idx = None#
Abstract base class for all joints.
- 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.model.StdLink(link: urdf_parser_py.urdf.Link, math: adam.core.spatial_math.SpatialMath)[source]#
Bases:
adam.model.Link
Standard Link class
- math#
- name#
- visuals#
- inertial#
- collisions#
- class adam.model.URDFModelFactory(path: str, math: adam.core.spatial_math.SpatialMath)[source]#
Bases:
adam.model.ModelFactory
This factory generates robot elements from urdf_parser_py
- Parameters:
ModelFactory – the Model factory
- math#
- urdf_desc#
- name#
- get_joints() list[adam.model.StdJoint] [source]#
- Returns:
build the list of the joints
- Return type:
list[StdJoint]
- get_links() list[adam.model.StdLink] [source]#
- Returns:
build the list of the links
- Return type:
list[StdLink]
A link is considered a “real” link if - it has an inertial - it has children - if it has no children and no inertial, it is at lest connected to the parent with a non fixed joint
- get_frames() list[adam.model.StdLink] [source]#
- Returns:
build the list of the links
- Return type:
list[StdLink]
A link is considered a “fake” link (frame) if - it has no inertial - it does not have children - it is connected to the parent with a fixed joint
- build_joint(joint: urdf_parser_py.urdf.Joint) adam.model.StdJoint [source]#
- build_link(link: urdf_parser_py.urdf.Link) adam.model.StdLink [source]#
- class adam.model.Node[source]#
The node class
- name: str#
- arcs: list[adam.model.abc_factories.Joint]#
- parent: adam.model.abc_factories.Link | None = None#
- parent_arc: adam.model.abc_factories.Joint | None = None#
- get_elements() tuple[adam.model.abc_factories.Link, adam.model.abc_factories.Joint, adam.model.abc_factories.Link] [source]#
returns the node with its parent arc and parent link
- class adam.model.Tree[source]#
Bases:
Iterable
The directed tree class
- root: str#
- static build_tree(links: list[adam.model.abc_factories.Link], joints: list[adam.model.abc_factories.Joint]) Tree [source]#
builds the tree from the connectivity of the elements
- get_ordered_nodes_list(start: str) list[str] [source]#
get the ordered list of the nodes, given the connectivity
- Parameters:
start (str) – the start node
- Returns:
the ordered list
- Return type:
list[str]
- classmethod get_children(node: Node, list: Tree.get_children.list)[source]#
Recursive method that finds children of child of child :param node: the analized node :type node: Node :param list: the list of the children that needs to be filled :type list: list
- get_idx_from_name(name: str) int [source]#
- Parameters:
name (str) – node name
- Returns:
the index of the node in the ordered list
- Return type:
int
- get_name_from_idx(idx: int) str [source]#
- Parameters:
idx (int) – the index in the ordered list
- Returns:
the corresponding node name
- Return type:
str
- get_node_from_name(name: str) Node [source]#
- Parameters:
name (str) – the node name
- Returns:
the node istance
- Return type:
- __iter__() Iterator[Node] [source]#
This method allows to iterate on the model :returns: the node istance :rtype: Node
- Yields:
Iterator[Node] – the list of the nodes
- __reversed__() Iterator[Node] [source]#
- Returns:
Node
- Yields:
Iterator[Node] – the reversed nodes list