Skip to content

Commit

Permalink
isort imports. Substitute List with list and similar.
Browse files Browse the repository at this point in the history
  • Loading branch information
Giulero committed Dec 30, 2024
1 parent 5f476dc commit eb710bb
Show file tree
Hide file tree
Showing 29 changed files with 117 additions and 129 deletions.
17 changes: 4 additions & 13 deletions src/adam/casadi/computations.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import casadi as cs
import numpy as np
from typing import Union

from adam.casadi.casadi_like import SpatialMath
from adam.core import RBDAlgorithms
Expand Down Expand Up @@ -224,9 +223,7 @@ def get_total_mass(self) -> float:
"""
return self.rbdalgos.get_total_mass()

def mass_matrix(
self, base_transform: cs.SX, joint_positions: cs.SX
):
def mass_matrix(self, base_transform: cs.SX, joint_positions: cs.SX):
"""Returns the Mass Matrix functions computed the CRBA
Args:
Expand All @@ -244,9 +241,7 @@ def mass_matrix(
M, _ = self.rbdalgos.crba(base_transform, joint_positions)
return M.array

def centroidal_momentum_matrix(
self, base_transform: cs.SX, joint_positions: cs.SX
):
def centroidal_momentum_matrix(self, base_transform: cs.SX, joint_positions: cs.SX):
"""Returns the Centroidal Momentum Matrix functions computed the CRBA
Args:
Expand Down Expand Up @@ -427,9 +422,7 @@ def coriolis_term(
np.zeros(6),
).array

def gravity_term(
self, base_transform: cs.SX, joint_positions: cs.SX
) -> cs.SX:
def gravity_term(self, base_transform: cs.SX, joint_positions: cs.SX) -> cs.SX:
"""Returns the gravity term of the floating-base dynamics equation,
using a reduced RNEA (no acceleration and external forces)
Expand All @@ -453,9 +446,7 @@ def gravity_term(
self.g,
).array

def CoM_position(
self, base_transform: cs.SX, joint_positions: cs.SX
) -> cs.SX:
def CoM_position(self, base_transform: cs.SX, joint_positions: cs.SX) -> cs.SX:
"""Returns the CoM positon
Args:
Expand Down
1 change: 0 additions & 1 deletion src/adam/jax/computations.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.


import jax.numpy as jnp
import numpy as np

Expand Down
2 changes: 1 addition & 1 deletion src/adam/model/__init__.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from .abc_factories import Joint, Link, ModelFactory, Inertial, Pose
from .abc_factories import Inertial, Joint, Link, ModelFactory, Pose
from .model import Model
from .std_factories.std_joint import StdJoint
from .std_factories.std_link import StdLink
Expand Down
23 changes: 11 additions & 12 deletions src/adam/model/abc_factories.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
import abc
import dataclasses
from typing import List

import numpy.typing as npt

Expand All @@ -11,8 +10,8 @@
class Pose:
"""Pose class"""

xyz: List
rpy: List
xyz: list
rpy: list


@dataclasses.dataclass
Expand Down Expand Up @@ -46,7 +45,7 @@ class Joint(abc.ABC):
parent: str
child: str
type: str
axis: List
axis: list
origin: Pose
limit: Limits
idx: int
Expand Down Expand Up @@ -126,9 +125,9 @@ class Link(abc.ABC):

math: SpatialMath
name: str
visuals: List
visuals: list
inertial: Inertial
collisions: List
collisions: list

@abc.abstractmethod
def spatial_inertia(self) -> npt.ArrayLike:
Expand Down Expand Up @@ -178,25 +177,25 @@ def build_joint(self) -> Joint:
pass

@abc.abstractmethod
def get_links(self) -> List[Link]:
def get_links(self) -> list[Link]:
"""
Returns:
List[Link]: the list of the link
list[Link]: the list of the link
"""
pass

@abc.abstractmethod
def get_frames(self) -> List[Link]:
def get_frames(self) -> list[Link]:
"""
Returns:
List[Link]: the list of the frames
list[Link]: the list of the frames
"""
pass

@abc.abstractmethod
def get_joints(self) -> List[Joint]:
def get_joints(self) -> list[Joint]:
"""
Returns:
List[Joint]: the list of the joints
list[Joint]: the list of the joints
"""
pass
6 changes: 2 additions & 4 deletions src/adam/model/conversions/idyntree.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,9 @@
import idyntree.bindings
import numpy as np
import urdf_parser_py.urdf
from typing import List


from adam.model.abc_factories import Joint, Link
from adam.model.model import Model
from adam.model.abc_factories import Link, Joint


def to_idyntree_solid_shape(
Expand Down Expand Up @@ -63,7 +61,7 @@ def to_idyntree_solid_shape(

def to_idyntree_link(
link: Link,
) -> [idyntree.bindings.Link, List[idyntree.bindings.SolidShape]]:
) -> [idyntree.bindings.Link, list[idyntree.bindings.SolidShape]]:
"""
Args:
link (Link): the link to convert
Expand Down
23 changes: 11 additions & 12 deletions src/adam/model/model.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
import dataclasses
from typing import Dict, List

from adam.model.abc_factories import Joint, Link, ModelFactory
from adam.model.tree import Tree
Expand All @@ -11,24 +10,24 @@ class Model:
Model class. It describes the robot using links and frames and their connectivity"""

name: str
links: Dict[str, Link]
frames: Dict[str, Link]
joints: Dict[str, Joint]
links: dict[str, Link]
frames: dict[str, Link]
joints: dict[str, Joint]
tree: Tree
NDoF: int
actuated_joints: List[str]
actuated_joints: list[str]

def __post_init__(self):
"""set the "length of the model as the number of links"""
self.N = len(self.links)

@staticmethod
def build(factory: ModelFactory, joints_name_list: List[str] = None) -> "Model":
def build(factory: ModelFactory, joints_name_list: list[str] = None) -> "Model":
"""generates the model starting from the list of joints and the links-joints factory
Args:
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
joints_name_list (list[str]): the list of the actuated joints
Returns:
Model: the model describing the robot
Expand Down Expand Up @@ -63,9 +62,9 @@ def build(factory: ModelFactory, joints_name_list: List[str] = None) -> "Model":
tree = Tree.build_tree(links=links_list, joints=joints_list)

# generate some useful dict
joints: Dict[str, Joint] = {joint.name: joint for joint in joints_list}
links: Dict[str, Link] = {link.name: link for link in links_list}
frames: Dict[str, Link] = {frame.name: frame for frame in frames_list}
joints: dict[str, Joint] = {joint.name: joint for joint in joints_list}
links: dict[str, Link] = {link.name: link for link in links_list}
frames: dict[str, Link] = {frame.name: frame for frame in frames_list}

return Model(
name=factory.name,
Expand All @@ -77,15 +76,15 @@ def build(factory: ModelFactory, joints_name_list: List[str] = None) -> "Model":
actuated_joints=joints_name_list,
)

def get_joints_chain(self, root: str, target: str) -> List[Joint]:
def get_joints_chain(self, root: str, target: str) -> list[Joint]:
"""generate the joints chains from a link to a link
Args:
root (str): the starting link
target (str): the target link
Returns:
List[Joint]: the list of the joints
list[Joint]: the list of the joints
"""

if target not in list(self.links) and target not in list(self.frames):
Expand Down
2 changes: 1 addition & 1 deletion src/adam/model/std_factories/std_link.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
import urdf_parser_py.urdf

from adam.core.spatial_math import SpatialMath
from adam.model import Link, Inertial, Pose
from adam.model import Inertial, Link, Pose


class StdLink(Link):
Expand Down
16 changes: 8 additions & 8 deletions src/adam/model/std_factories/std_model.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
import os
import pathlib
from typing import List
import xml.etree.ElementTree as ET
import os

import urdf_parser_py.urdf

from adam.core.spatial_math import SpatialMath
Expand Down Expand Up @@ -85,17 +85,17 @@ def __init__(self, path: str, math: SpatialMath):
)
self.name = self.urdf_desc.name

def get_joints(self) -> List[StdJoint]:
def get_joints(self) -> list[StdJoint]:
"""
Returns:
List[StdJoint]: build the list of the joints
list[StdJoint]: build the list of the joints
"""
return [self.build_joint(j) for j in self.urdf_desc.joints]

def get_links(self) -> List[StdLink]:
def get_links(self) -> list[StdLink]:
"""
Returns:
List[StdLink]: build the list of the links
list[StdLink]: build the list of the links
A link is considered a "real" link if
- it has an inertial
Expand All @@ -116,10 +116,10 @@ def get_links(self) -> List[StdLink]:
)
]

def get_frames(self) -> List[StdLink]:
def get_frames(self) -> list[StdLink]:
"""
Returns:
List[StdLink]: build the list of the links
list[StdLink]: build the list of the links
A link is considered a "fake" link (frame) if
- it has no inertial
Expand Down
28 changes: 14 additions & 14 deletions src/adam/model/tree.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
import dataclasses
from typing import Dict, Iterable, List, Tuple, Union
from typing import Iterable, Union

from adam.model.abc_factories import Joint, Link

Expand All @@ -10,19 +10,19 @@ class Node:

name: str
link: Link
arcs: List[Joint]
children: List["Node"]
arcs: list[Joint]
children: list["Node"]
parent: Union[Link, None] = None
parent_arc: Union[Joint, None] = None

def __hash__(self) -> int:
return hash(self.name)

def get_elements(self) -> Tuple[Link, Joint, Link]:
def get_elements(self) -> tuple[Link, Joint, Link]:
"""returns the node with its parent arc and parent link
Returns:
Tuple[Link, Joint, Link]: the node, the parent_arc, the parent_link
tuple[Link, Joint, Link]: the node, the parent_arc, the parent_link
"""
return self.link, self.parent_arc, self.parent

Expand All @@ -31,24 +31,24 @@ def get_elements(self) -> Tuple[Link, Joint, Link]:
class Tree(Iterable):
"""The directed tree class"""

graph: Dict
graph: dict
root: str

def __post_init__(self):
self.ordered_nodes_list = self.get_ordered_nodes_list(self.root)

@staticmethod
def build_tree(links: List[Link], joints: List[Joint]) -> "Tree":
def build_tree(links: list[Link], joints: list[Joint]) -> "Tree":
"""builds the tree from the connectivity of the elements
Args:
links (List[Link])
joints (List[Joint])
links (list[Link])
joints (list[Joint])
Returns:
Tree: the directed tree
"""
nodes: Dict[str, Node] = {
nodes: dict[str, Node] = {
l.name: Node(
name=l.name, link=l, arcs=[], children=[], parent=None, parent_arc=None
)
Expand Down Expand Up @@ -81,25 +81,25 @@ def print(self, root):

pptree.print_tree(self.graph[root])

def get_ordered_nodes_list(self, start: str) -> List[str]:
def get_ordered_nodes_list(self, start: str) -> list[str]:
"""get the ordered list of the nodes, given the connectivity
Args:
start (str): the start node
Returns:
List[str]: the ordered list
list[str]: the ordered list
"""
ordered_list = [start]
self.get_children(self.graph[start], ordered_list)
return ordered_list

@classmethod
def get_children(cls, node: Node, list: List):
def get_children(cls, node: Node, list: list):
"""Recursive method that finds children of child of child
Args:
node (Node): the analized node
list (List): the list of the children that needs to be filled
list (list): the list of the children that needs to be filled
"""
if node.children is not []:
for child in node.children:
Expand Down
6 changes: 2 additions & 4 deletions src/adam/parametric/casadi/computations_parametric.py
Original file line number Diff line number Diff line change
@@ -1,15 +1,13 @@
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

from typing import List, Union

import casadi as cs
import numpy as np

from adam.casadi.casadi_like import SpatialMath
from adam.core import RBDAlgorithms
from adam.core.constants import Representations
from adam.model import Model
from adam.parametric.model import URDFParametricModelFactory, ParametricLink
from adam.parametric.model import ParametricLink, URDFParametricModelFactory


class KinDynComputationsParametric:
Expand Down Expand Up @@ -260,7 +258,7 @@ def get_total_mass(self) -> cs.Function:
"m", [self.length_multiplier, self.densities], [m], self.f_opts
)

def get_original_densities(self) -> List[float]:
def get_original_densities(self) -> list[float]:
"""Returns the original densities of the parametric links
Returns:
Expand Down
Loading

0 comments on commit eb710bb

Please sign in to comment.