adam.model

Contents

adam.model#

Submodules#

Classes#

Inertial

Inertial description

Joint

Base Joint class. You need to fill at least these fields

Link

Base Link class. You need to fill at least these fields

ModelFactory

The abstract class of the model factory.

Pose

Pose class

Model

Model class. It describes the robot using links and frames and their connectivity

StdJoint

Standard Joint class

StdLink

Standard Link class

URDFModelFactory

This factory generates robot elements from urdf_parser_py

Node

The node class

Tree

The directed tree class

Package Contents#

class adam.model.Inertial[source]#

Inertial description

mass: numpy.typing.ArrayLike#
inertia: Inertia#
origin: Pose#
static zero() Inertial[source]#

Returns an Inertial object with zero mass and inertia

set_mass(mass: numpy.typing.ArrayLike) Inertial[source]#

Set the mass of the inertial object

set_inertia(inertia: Inertia) Inertial[source]#

Set the inertia of the inertial object

set_origin(origin: Pose) Inertial[source]#

Set the origin of the inertial object

class adam.model.Joint[source]#

Bases: abc.ABC

Base Joint class. You need to fill at least these fields

math: adam.core.spatial_math.SpatialMath#
name: str#
parent: str#
child: str#
type: str#
axis: list#
origin: Pose#
limit: Limits#
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

abstractmethod motion_subspace() numpy.typing.ArrayLike[source]#
Returns:

motion subspace of the joint

Return type:

npt.ArrayLike

abstractmethod homogeneous(q: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#
Parameters:

q (npt.ArrayLike) – joint value

Returns:

homogeneous transform given the joint value

Return type:

npt.ArrayLike

Bases: abc.ABC

Base Link class. You need to fill at least these fields

math: adam.core.spatial_math.SpatialMath#
name: str#
visuals: list#
inertial: Inertial#
collisions: list#
abstractmethod spatial_inertia() numpy.typing.ArrayLike[source]#
Returns:

the 6x6 inertia matrix expressed at

the origin of the link (with rotation)

Return type:

npt.ArrayLike

abstractmethod homogeneous() numpy.typing.ArrayLike[source]#
Returns:

the homogeneous transform of the link

Return type:

npt.ArrayLike

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

math: adam.core.spatial_math.SpatialMath#
name: str#

build the single link :returns: Link

abstractmethod build_joint() Joint[source]#

build the single joint

Returns:

Joint

Returns:

the list of the link

Return type:

list[Link]

abstractmethod get_frames() list[Link][source]#
Returns:

the list of the frames

Return type:

list[Link]

abstractmethod get_joints() list[Joint][source]#
Returns:

the list of the joints

Return type:

list[Joint]

class adam.model.Pose[source]#

Pose class

xyz: list#
rpy: list#
class adam.model.Model[source]#

Model class. It describes the robot using links and frames and their connectivity

name: str#
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:

Model

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]

get_total_mass() float[source]#

total mass of the robot

Returns:

the total mass of the robot

Return type:

float

print_table()[source]#

print the table that describes the connectivity between the elements. You need rich to use it

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

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

motion_subspace() numpy.typing.ArrayLike[source]#
Parameters:

joint (Joint) – Joint

Returns:

motion subspace of the joint

Return type:

npt.ArrayLike

Bases: adam.model.Link

Standard Link class

math#
name#
visuals#
inertial#
collisions#
spatial_inertia() numpy.typing.ArrayLike[source]#
Returns:

the 6x6 inertia matrix expressed at

the origin of the link (with rotation)

Return type:

npt.ArrayLike

homogeneous() numpy.typing.ArrayLike[source]#
Returns:

the homogeneous transform of the link

Return type:

npt.ArrayLike

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]

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]#
Parameters:

joint (Joint) – the urdf_parser_py joint

Returns:

our joint representation

Return type:

StdJoint

Parameters:

link (Link) – the urdf_parser_py link

Returns:

our link representation

Return type:

StdLink

class adam.model.Node[source]#

The node class

name: str#
arcs: list[adam.model.abc_factories.Joint]#
children: list[Node]#
parent: adam.model.abc_factories.Link | None = None#
parent_arc: adam.model.abc_factories.Joint | None = None#
__hash__() int[source]#
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

Returns:

the node, the parent_arc, the parent_link

Return type:

tuple[Link, Joint, Link]

class adam.model.Tree[source]#

Bases: Iterable

The directed tree class

graph: dict[str, Node]#
root: str#
__post_init__()[source]#
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

Parameters:
Returns:

the directed tree

Return type:

Tree

print(root)[source]#

prints the tree

Parameters:

root (str) – the root of the tree

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:

Node

__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

__getitem__(key) Node[source]#

get the item at key in the model

Parameters:

key (Union[int, Slice]) – _description_

Returns:

_description_

Return type:

Node

__len__() int[source]#
Returns:

the length of the model

Return type:

int