Skip to content
Merged
Show file tree
Hide file tree
Changes from 21 commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
39aabbc
Fix wrong comments
Giulero Dec 27, 2024
21b1a81
Update copyright notices to remove year specification
Giulero Dec 27, 2024
8682e2b
Update copyright notice to remove year specification
Giulero Dec 27, 2024
f8e5c8a
Remove unused import from core module
Giulero Dec 30, 2024
5f476dc
Update copyright notices to remove year specification
Giulero Dec 30, 2024
eb710bb
isort imports. Substitute List with list and similar.
Giulero Dec 30, 2024
97f814f
Fix return type
Giulero Dec 30, 2024
b5b839b
Fix another return type
Giulero Dec 30, 2024
5ca24e5
Fix stupid typo
Giulero Dec 30, 2024
8ddbf04
Specify type for graph attribute and improve error message for multip…
Giulero Jan 2, 2025
c8adbbc
Refactor model to use property for link number instead of post init
Giulero Jan 2, 2025
a8b110c
Deprecate root_link parameter in casadi KinDynComputations constructo…
Giulero Jan 2, 2025
931bfaa
Deprecate root_link parameter in jax KinDynComputations constructors …
Giulero Jan 2, 2025
3f6b84b
Deprecate root_link parameter in numpy KinDynComputations constructor…
Giulero Jan 2, 2025
f8596e0
Deprecate root_link parameter in casadi KinDynComputationsParametric…
Giulero Jan 2, 2025
f60e4e0
Deprecate root_link parameter in jax KinDynComputationsParametric con…
Giulero Jan 2, 2025
e8b4be3
Deprecate root_link parameter in numpy KinDynComputationsParametric c…
Giulero Jan 2, 2025
ac697b8
Deprecate root_link parameter in pytorch KinDynComputationsParametric…
Giulero Jan 2, 2025
8b39b3c
Deprecate root_link parameter in pytorch KinDynComputations construct…
Giulero Jan 2, 2025
d665eae
Comply with black
Giulero Jan 2, 2025
3b46c9f
Investigate if moving the import solves the circular import
Giulero Jan 2, 2025
af95f33
Revert back Isorting
Giulero Jan 3, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion docs/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
# https://www.sphinx-doc.org/en/master/usage/configuration.html#project-information

project = "adam"
copyright = "2021, Artificial and Mechanical Intelligence Lab"
copyright = "Artificial and Mechanical Intelligence Lab"
author = "Artificial and Mechanical Intelligence Lab"
# get release from git tag

Expand Down
3 changes: 1 addition & 2 deletions setup.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.

from setuptools import setup

Expand Down
4 changes: 1 addition & 3 deletions src/adam/__init__.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

from adam.core import Representations
4 changes: 1 addition & 3 deletions src/adam/casadi/__init__.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

from .casadi_like import CasadiLike
from .computations import KinDynComputations
4 changes: 1 addition & 3 deletions src/adam/casadi/casadi_like.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

from dataclasses import dataclass
from typing import Union
Expand Down
147 changes: 69 additions & 78 deletions src/adam/casadi/computations.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,7 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

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 All @@ -13,23 +10,21 @@


class KinDynComputations:
"""This is a small class that retrieves robot quantities represented in a symbolic fashion using CasADi
in mixed representation, for Floating Base systems - as humanoid robots.
"""
"""Class that retrieves robot quantities using CasADi for Floating Base systems."""

def __init__(
self,
urdfstring: str,
joints_name_list: list = None,
root_link: str = "root_link",
root_link: str = None,
gravity: np.array = np.array([0.0, 0.0, -9.80665, 0.0, 0.0, 0.0]),
f_opts: dict = dict(jit=False, jit_options=dict(flags="-Ofast"), cse=True),
) -> None:
"""
Args:
urdfstring (str): either path or string of the urdf
joints_name_list (list): list of the actuated joints
root_link (str, optional): the first link. Defaults to 'root_link'.
root_link (str, optional): Deprecated. The root link is automatically chosen as the link with no parent in the URDF. Defaults to None.
"""
math = SpatialMath()
factory = URDFModelFactory(path=urdfstring, math=math)
Expand All @@ -38,6 +33,10 @@ def __init__(
self.NDoF = self.rbdalgos.NDoF
self.g = gravity
self.f_opts = f_opts
if root_link is not None:
raise DeprecationWarning(
"The root_link argument is not used. The root link is automatically chosen as the link with no parent in the URDF"
)

def set_frame_velocity_representation(
self, representation: Representations
Expand All @@ -57,7 +56,7 @@ def mass_matrix_fun(self) -> cs.Function:
"""
base_transform = cs.SX.sym("H", 4, 4)
joint_positions = cs.SX.sym("s", self.NDoF)
[M, _] = self.rbdalgos.crba(base_transform, joint_positions)
M, _ = self.rbdalgos.crba(base_transform, joint_positions)
return cs.Function(
"M", [base_transform, joint_positions], [M.array], self.f_opts
)
Expand All @@ -70,7 +69,7 @@ def centroidal_momentum_matrix_fun(self) -> cs.Function:
"""
base_transform = cs.SX.sym("H", 4, 4)
joint_positions = cs.SX.sym("s", self.NDoF)
[_, Jcm] = self.rbdalgos.crba(base_transform, joint_positions)
_, Jcm = self.rbdalgos.crba(base_transform, joint_positions)
return cs.Function(
"Jcm", [base_transform, joint_positions], [Jcm.array], self.f_opts
)
Expand Down Expand Up @@ -228,55 +227,51 @@ def get_total_mass(self) -> float:
"""
return self.rbdalgos.get_total_mass()

def mass_matrix(
self, base_transform: Union[cs.SX, cs.DM], joint_positions: Union[cs.SX, cs.DM]
):
def mass_matrix(self, base_transform: cs.SX, joint_positions: cs.SX):
"""Returns the Mass Matrix functions computed the CRBA

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position

Returns:
M (Union[cs.SX, cs.DM]): Mass Matrix
M (cs.SX): Mass Matrix
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
"You are using casadi MX. Please use the function KinDynComputations.mass_matrix_fun()"
)

[M, _] = self.rbdalgos.crba(base_transform, joint_positions)
M, _ = self.rbdalgos.crba(base_transform, joint_positions)
return M.array

def centroidal_momentum_matrix(
self, base_transform: Union[cs.SX, cs.DM], joint_positions: Union[cs.SX, cs.DM]
):
def centroidal_momentum_matrix(self, base_transform: cs.SX, joint_positions: cs.SX):
"""Returns the Centroidal Momentum Matrix functions computed the CRBA

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position

Returns:
Jcc (Union[cs.SX, cs.DM]): Centroidal Momentum matrix
Jcc (cs.SX): Centroidal Momentum matrix
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
"You are using casadi MX. Please use the function KinDynComputations.centroidal_momentum_matrix_fun()"
)

[_, Jcm] = self.rbdalgos.crba(base_transform, joint_positions)
_, Jcm = self.rbdalgos.crba(base_transform, joint_positions)
return Jcm.array

def relative_jacobian(self, frame: str, joint_positions: Union[cs.SX, cs.DM]):
def relative_jacobian(self, frame: str, joint_positions: cs.SX):
"""Returns the Jacobian between the root link and a specified frame frames

Args:
frame (str): The tip of the chain
joint_positions (Union[cs.SX, cs.DM]): The joints position
joint_positions (cs.SX): The joints position

Returns:
J (Union[cs.SX, cs.DM]): The Jacobian between the root and the frame
J (cs.SX): The Jacobian between the root and the frame
"""
if isinstance(joint_positions, cs.MX):
raise ValueError(
Expand All @@ -288,22 +283,22 @@ def relative_jacobian(self, frame: str, joint_positions: Union[cs.SX, cs.DM]):
def jacobian_dot(
self,
frame: str,
base_transform: Union[cs.SX, cs.DM],
joint_positions: Union[cs.SX, cs.DM],
base_velocity: Union[cs.SX, cs.DM],
joint_velocities: Union[cs.SX, cs.DM],
) -> Union[cs.SX, cs.DM]:
base_transform: cs.SX,
joint_positions: cs.SX,
base_velocity: cs.SX,
joint_velocities: cs.SX,
) -> cs.SX:
"""Returns the Jacobian derivative relative to the specified frame

Args:
frame (str): The frame to which the jacobian will be computed
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_velocity (Union[cs.SX, cs.DM]): The base velocity in mixed representation
joint_velocities (Union[cs.SX, cs.DM]): The joint velocities
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position
base_velocity (cs.SX): The base velocity in mixed representation
joint_velocities (cs.SX): The joint velocities

Returns:
Jdot (Union[cs.SX, cs.DM]): The Jacobian derivative relative to the frame
Jdot (cs.SX): The Jacobian derivative relative to the frame
"""
if (
isinstance(base_transform, cs.MX)
Expand All @@ -321,18 +316,18 @@ def jacobian_dot(
def forward_kinematics(
self,
frame: str,
base_transform: Union[cs.SX, cs.DM],
joint_positions: Union[cs.SX, cs.DM],
base_transform: cs.SX,
joint_positions: cs.SX,
):
"""Computes the forward kinematics relative to the specified frame

Args:
frame (str): The frame to which the fk will be computed
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position

Returns:
H (Union[cs.SX, cs.DM]): The fk represented as Homogenous transformation matrix
H (cs.SX): The fk represented as Homogenous transformation matrix
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
Expand All @@ -347,12 +342,12 @@ def jacobian(self, frame: str, base_transform, joint_positions):
"""Returns the Jacobian relative to the specified frame

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
s (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
s (cs.SX): The joints position
frame (str): The frame to which the jacobian will be computed

Returns:
J_tot (Union[cs.SX, cs.DM]): The Jacobian relative to the frame
J_tot (cs.SX): The Jacobian relative to the frame
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
Expand All @@ -363,22 +358,22 @@ def jacobian(self, frame: str, base_transform, joint_positions):

def bias_force(
self,
base_transform: Union[cs.SX, cs.DM],
joint_positions: Union[cs.SX, cs.DM],
base_velocity: Union[cs.SX, cs.DM],
joint_velocities: Union[cs.SX, cs.DM],
) -> Union[cs.SX, cs.DM]:
base_transform: cs.SX,
joint_positions: cs.SX,
base_velocity: cs.SX,
joint_velocities: cs.SX,
) -> cs.SX:
"""Returns the bias force of the floating-base dynamics equation,
using a reduced RNEA (no acceleration and external forces)

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_velocity (Union[cs.SX, cs.DM]): The base velocity in mixed representation
joint_velocities (Union[cs.SX, cs.DM]): The joints velocity
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position
base_velocity (cs.SX): The base velocity in mixed representation
joint_velocities (cs.SX): The joints velocity

Returns:
h (Union[cs.SX, cs.DM]): the bias force
h (cs.SX): the bias force
"""
if (
isinstance(base_transform, cs.MX)
Expand All @@ -396,22 +391,22 @@ def bias_force(

def coriolis_term(
self,
base_transform: Union[cs.SX, cs.DM],
joint_positions: Union[cs.SX, cs.DM],
base_velocity: Union[cs.SX, cs.DM],
joint_velocities: Union[cs.SX, cs.DM],
) -> Union[cs.SX, cs.DM]:
base_transform: cs.SX,
joint_positions: cs.SX,
base_velocity: cs.SX,
joint_velocities: cs.SX,
) -> cs.SX:
"""Returns the coriolis term of the floating-base dynamics equation,
using a reduced RNEA (no acceleration and external forces)

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_velocity (Union[cs.SX, cs.DM]): The base velocity in mixed representation
joint_velocities (Union[cs.SX, cs.DM]): The joints velocity
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position
base_velocity (cs.SX): The base velocity in mixed representation
joint_velocities (cs.SX): The joints velocity

Returns:
C (Union[cs.SX, cs.DM]): the Coriolis term
C (cs.SX): the Coriolis term
"""
if (
isinstance(base_transform, cs.MX)
Expand All @@ -431,18 +426,16 @@ def coriolis_term(
np.zeros(6),
).array

def gravity_term(
self, base_transform: Union[cs.SX, cs.DM], joint_positions: Union[cs.SX, cs.DM]
) -> Union[cs.SX, cs.DM]:
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)

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position

Returns:
G (Union[cs.SX, cs.DM]): the gravity term
G (cs.SX): the gravity term
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
Expand All @@ -457,17 +450,15 @@ def gravity_term(
self.g,
).array

def CoM_position(
self, base_transform: Union[cs.SX, cs.DM], joint_positions: Union[cs.SX, cs.DM]
) -> Union[cs.SX, cs.DM]:
def CoM_position(self, base_transform: cs.SX, joint_positions: cs.SX) -> cs.SX:
"""Returns the CoM positon

Args:
base_transform (Union[cs.SX, cs.DM]): The homogenous transform from base to world frame
joint_positions (Union[cs.SX, cs.DM]): The joints position
base_transform (cs.SX): The homogenous transform from base to world frame
joint_positions (cs.SX): The joints position

Returns:
CoM (Union[cs.SX, cs.DM]): The CoM position
CoM (cs.SX): The CoM position
"""
if isinstance(base_transform, cs.MX) and isinstance(joint_positions, cs.MX):
raise ValueError(
Expand Down
4 changes: 1 addition & 3 deletions src/adam/core/__init__.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

from .constants import Representations
from .rbd_algorithms import RBDAlgorithms
Expand Down
5 changes: 2 additions & 3 deletions src/adam/core/rbd_algorithms.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.

import numpy.typing as npt

from adam.core.constants import Representations
Expand Down
5 changes: 2 additions & 3 deletions src/adam/jax/__init__.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
# Copyright (C) 2021 Istituto Italiano di Tecnologia (IIT). All rights reserved.
# This software may be modified and distributed under the terms of the
# GNU Lesser General Public License v2.1 or any later version.
# Copyright (C) Istituto Italiano di Tecnologia (IIT). All rights reserved.


from .computations import KinDynComputations
from .jax_like import JaxLike
Loading
Loading