diff --git a/examples/iCub_example_casadi.ipynb b/examples/iCub_example_casadi.ipynb index c2fe6739..a3e640f7 100644 --- a/examples/iCub_example_casadi.ipynb +++ b/examples/iCub_example_casadi.ipynb @@ -10,10 +10,11 @@ "from adam.geometry import utils\n", "import numpy as np\n", "import casadi as cs\n", - "import gym_ignition_models" + "import icub_models" ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -26,7 +27,7 @@ "metadata": {}, "outputs": [], "source": [ - "urdf_path = gym_ignition_models.get_model_file(\"iCubGazeboV2_5\")\n", + "urdf_path = icub_models.get_model_file(\"iCubGazeboV2_5\")\n", "# The joint list\n", "joints_name_list = [\n", " 'torso_pitch', 'torso_roll', 'torso_yaw', 'l_shoulder_pitch',\n", @@ -41,6 +42,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -63,6 +65,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -118,6 +121,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -150,6 +154,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -176,6 +181,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -201,6 +207,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -233,6 +240,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -265,6 +273,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -295,6 +304,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -321,6 +331,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -347,6 +358,7 @@ ] }, { + "attachments": {}, "cell_type": "markdown", "metadata": {}, "source": [ @@ -392,7 +404,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.8.10" + "version": "3.10.11" }, "metadata": { "interpreter": { diff --git a/setup.cfg b/setup.cfg index 8e7060e9..e87d9ec9 100644 --- a/setup.cfg +++ b/setup.cfg @@ -51,8 +51,9 @@ test = torch pytest idyntree - gym-ignition-models + icub-models black + gym-ignition-models all = jax jaxlib diff --git a/src/adam/casadi/__init__.py b/src/adam/casadi/__init__.py index c42c5cb8..c3bc4744 100644 --- a/src/adam/casadi/__init__.py +++ b/src/adam/casadi/__init__.py @@ -3,3 +3,4 @@ # GNU Lesser General Public License v2.1 or any later version. from .computations import KinDynComputations +from .casadi_like import CasadiLike diff --git a/src/adam/casadi/casadi_like.py b/src/adam/casadi/casadi_like.py index 3666ae06..522a74e0 100644 --- a/src/adam/casadi/casadi_like.py +++ b/src/adam/casadi/casadi_like.py @@ -8,23 +8,26 @@ import casadi as cs import numpy.typing as npt -from adam.core.spatial_math import ArrayLike +from adam.core.spatial_math import ArrayLike, ArrayLikeFactory, SpatialMath +from adam.numpy import NumpyLike @dataclass class CasadiLike(ArrayLike): + """Wrapper class for Casadi types""" + array: Union[cs.SX, cs.DM] def __matmul__(self, other: Union["CasadiLike", npt.ArrayLike]) -> "CasadiLike": """Overrides @ operator""" - if type(self) is type(other): + if type(other) in [CasadiLike, NumpyLike]: return CasadiLike(self.array @ other.array) else: return CasadiLike(self.array @ other) def __rmatmul__(self, other: Union["CasadiLike", npt.ArrayLike]) -> "CasadiLike": """Overrides @ operator""" - if type(self) is type(other): + if type(other) in [CasadiLike, NumpyLike]: return CasadiLike(other.array @ self.array) else: return CasadiLike(other @ self.array) @@ -98,6 +101,8 @@ def T(self) -> "CasadiLike": """ return CasadiLike(self.array.T) + +class CasadiLikeFactory(ArrayLikeFactory): @staticmethod def zeros(*x: int) -> "CasadiLike": """ @@ -106,19 +111,6 @@ def zeros(*x: int) -> "CasadiLike": """ return CasadiLike(cs.SX.zeros(*x)) - @staticmethod - def vertcat(*x) -> "CasadiLike": - """ - Returns: - CasadiLike: vertical concatenation of elements - """ - # here the logic is a bit convoluted: x is a tuple containing CasadiLike - # cs.vertcat accepts *args. A list of cs types is created extracting the value - # from the CasadiLike stored in the tuple x. - # Then the list is unpacked with the * operator. - y = [xi.array if isinstance(xi, CasadiLike) else xi for xi in x] - return CasadiLike(cs.vertcat(*y)) - @staticmethod def eye(x: int) -> "CasadiLike": """ @@ -130,6 +122,19 @@ def eye(x: int) -> "CasadiLike": """ return CasadiLike(cs.SX.eye(x)) + @staticmethod + def array(*x) -> "CasadiLike": + """ + Returns: + CasadiLike: Vector wrapping *x + """ + return CasadiLike(cs.DM(*x)) + + +class SpatialMath(SpatialMath): + def __init__(self): + super().__init__(CasadiLikeFactory) + @staticmethod def skew(x: Union["CasadiLike", npt.ArrayLike]) -> "CasadiLike": """ @@ -144,14 +149,6 @@ def skew(x: Union["CasadiLike", npt.ArrayLike]) -> "CasadiLike": else: return CasadiLike(cs.skew(x)) - @staticmethod - def array(*x) -> "CasadiLike": - """ - Returns: - CasadiLike: Vector wrapping *x - """ - return CasadiLike(cs.DM(*x)) - @staticmethod def sin(x: npt.ArrayLike) -> "CasadiLike": """ @@ -185,3 +182,21 @@ def outer(x: npt.ArrayLike, y: npt.ArrayLike) -> "CasadiLike": CasadiLike: outer product between x and y """ return CasadiLike(cs.np.outer(x, y)) + + @staticmethod + def vertcat(*x) -> "CasadiLike": + """ + Returns: + CasadiLike: vertical concatenation of elements + """ + # here the logic is a bit convoluted: x is a tuple containing CasadiLike + # cs.vertcat accepts *args. A list of cs types is created extracting the value + # from the CasadiLike stored in the tuple x. + # Then the list is unpacked with the * operator. + y = [xi.array if isinstance(xi, CasadiLike) else xi for xi in x] + return CasadiLike(cs.vertcat(*y)) + + +if __name__ == "__main__": + math = SpatialMath() + print(math.eye(3)) diff --git a/src/adam/casadi/computations.py b/src/adam/casadi/computations.py index 1e6d8abf..6d8ed568 100644 --- a/src/adam/casadi/computations.py +++ b/src/adam/casadi/computations.py @@ -5,11 +5,12 @@ import casadi as cs import numpy as np -from adam.casadi.casadi_like import CasadiLike -from adam.core.rbd_algorithms import RBDAlgorithms +from adam.casadi.casadi_like import SpatialMath +from adam.core import RBDAlgorithms +from adam.model import Model, URDFModelFactory -class KinDynComputations(RBDAlgorithms, CasadiLike): +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. """ @@ -28,12 +29,12 @@ def __init__( joints_name_list (list): list of the actuated joints root_link (str, optional): the first link. Defaults to 'root_link'. """ - super().__init__( - urdfstring=urdfstring, - joints_name_list=joints_name_list, - root_link=root_link, - gravity=gravity, - ) + math = SpatialMath() + factory = URDFModelFactory(path=urdfstring, math=math) + model = Model.build(factory=factory, joints_name_list=joints_name_list) + self.rbdalgos = RBDAlgorithms(model=model, math=math) + self.NDoF = self.rbdalgos.NDoF + self.g = gravity self.f_opts = f_opts def mass_matrix_fun(self) -> cs.Function: @@ -44,7 +45,7 @@ def mass_matrix_fun(self) -> cs.Function: """ T_b = cs.SX.sym("T_b", 4, 4) s = cs.SX.sym("s", self.NDoF) - [M, _] = super().crba(T_b, s) + [M, _] = self.rbdalgos.crba(T_b, s) return cs.Function("M", [T_b, s], [M.array], self.f_opts) def centroidal_momentum_matrix_fun(self) -> cs.Function: @@ -55,7 +56,7 @@ def centroidal_momentum_matrix_fun(self) -> cs.Function: """ T_b = cs.SX.sym("T_b", 4, 4) s = cs.SX.sym("s", self.NDoF) - [_, Jcm] = super().crba(T_b, s) + [_, Jcm] = self.rbdalgos.crba(T_b, s) return cs.Function("Jcm", [T_b, s], [Jcm.array], self.f_opts) def forward_kinematics_fun(self, frame: str) -> cs.Function: @@ -69,7 +70,7 @@ def forward_kinematics_fun(self, frame: str) -> cs.Function: """ s = cs.SX.sym("s", self.NDoF) T_b = cs.SX.sym("T_b", 4, 4) - T_fk = super().forward_kinematics(frame, T_b, s) + T_fk = self.rbdalgos.forward_kinematics(frame, T_b, s) return cs.Function("T_fk", [T_b, s], [T_fk.array], self.f_opts) def jacobian_fun(self, frame: str) -> cs.Function: @@ -83,7 +84,7 @@ def jacobian_fun(self, frame: str) -> cs.Function: """ s = cs.SX.sym("s", self.NDoF) T_b = cs.SX.sym("T_b", 4, 4) - J_tot = super().jacobian(frame, T_b, s) + J_tot = self.rbdalgos.jacobian(frame, T_b, s) return cs.Function("J_tot", [T_b, s], [J_tot.array], self.f_opts) def relative_jacobian_fun(self, frame: str) -> cs.Function: @@ -96,7 +97,7 @@ def relative_jacobian_fun(self, frame: str) -> cs.Function: J (casADi function): The Jacobian between the root and the frame """ s = cs.SX.sym("s", self.NDoF) - J = super().relative_jacobian(frame, s) + J = self.rbdalgos.relative_jacobian(frame, s) return cs.Function("J", [s], [J.array], self.f_opts) def CoM_position_fun(self) -> cs.Function: @@ -107,7 +108,7 @@ def CoM_position_fun(self) -> cs.Function: """ s = cs.SX.sym("s", self.NDoF) T_b = cs.SX.sym("T_b", 4, 4) - com_pos = super().CoM_position(T_b, s) + com_pos = self.rbdalgos.CoM_position(T_b, s) return cs.Function("CoM_pos", [T_b, s], [com_pos.array], self.f_opts) def bias_force_fun(self) -> cs.Function: @@ -121,7 +122,7 @@ def bias_force_fun(self) -> cs.Function: s = cs.SX.sym("s", self.NDoF) v_b = cs.SX.sym("v_b", 6) s_dot = cs.SX.sym("s_dot", self.NDoF) - h = super().rnea(T_b, s, v_b, s_dot, self.g) + h = self.rbdalgos.rnea(T_b, s, v_b, s_dot, self.g) return cs.Function("h", [T_b, s, v_b, s_dot], [h.array], self.f_opts) def coriolis_term_fun(self) -> cs.Function: @@ -136,7 +137,7 @@ def coriolis_term_fun(self) -> cs.Function: v_b = cs.SX.sym("v_b", 6) q_dot = cs.SX.sym("q_dot", self.NDoF) # set in the bias force computation the gravity term to zero - C = super().rnea(T_b, q, v_b, q_dot, np.zeros(6)) + C = self.rbdalgos.rnea(T_b, q, v_b, q_dot, np.zeros(6)) return cs.Function("C", [T_b, q, v_b, q_dot], [C.array], self.f_opts) def gravity_term_fun(self) -> cs.Function: @@ -149,5 +150,25 @@ def gravity_term_fun(self) -> cs.Function: T_b = cs.SX.sym("T_b", 4, 4) q = cs.SX.sym("q", self.NDoF) # set in the bias force computation the velocity to zero - G = super().rnea(T_b, q, np.zeros(6), np.zeros(self.NDoF), self.g) + G = self.rbdalgos.rnea(T_b, q, np.zeros(6), np.zeros(self.NDoF), self.g) return cs.Function("G", [T_b, q], [G.array], self.f_opts) + + def forward_kinematics(self, frame, T_b, s) -> cs.Function: + """Computes the forward kinematics relative to the specified frame + + Args: + frame (str): The frame to which the fk will be computed + + Returns: + T_fk (casADi function): The fk represented as Homogenous transformation matrix + """ + + return self.rbdalgos.forward_kinematics(frame, T_b, s) + + def get_total_mass(self) -> float: + """Returns the total mass of the robot + + Returns: + mass: The total mass + """ + return self.rbdalgos.get_total_mass() diff --git a/src/adam/core/__init__.py b/src/adam/core/__init__.py index a05fe4c4..a5a25cd9 100644 --- a/src/adam/core/__init__.py +++ b/src/adam/core/__init__.py @@ -2,4 +2,5 @@ # This software may be modified and distributed under the terms of the # GNU Lesser General Public License v2.1 or any later version. -from . import rbd_algorithms, spatial_math, urdf_tree +from .rbd_algorithms import RBDAlgorithms +from .spatial_math import SpatialMath diff --git a/src/adam/core/rbd_algorithms.py b/src/adam/core/rbd_algorithms.py index 84449210..520533f4 100644 --- a/src/adam/core/rbd_algorithms.py +++ b/src/adam/core/rbd_algorithms.py @@ -3,23 +3,16 @@ # GNU Lesser General Public License v2.1 or any later version. import numpy.typing as npt +from adam.model import Model, Node from adam.core.spatial_math import SpatialMath -from adam.core.urdf_tree import URDFTree -import dataclasses -class RBDAlgorithms(SpatialMath): - """This is a small abstract class that implements Rigid body algorithms retrieving robot quantities represented +class RBDAlgorithms: + """This is a small class that implements Rigid body algorithms retrieving robot quantities represented in mixed representation, for Floating Base systems - as humanoid robots. """ - def __init__( - self, - urdfstring: str, - joints_name_list: list, - root_link: str, - gravity: npt.ArrayLike, - ) -> None: + def __init__(self, model: Model, math: SpatialMath) -> None: """ Args: urdfstring (str): path of the urdf @@ -27,20 +20,10 @@ def __init__( root_link (str, optional): the first link. Defaults to 'root_link'. """ - urdf_tree = URDFTree(urdfstring, joints_name_list, root_link) - self.robot_desc = urdf_tree.robot_desc - self.joints_list = urdf_tree.get_joints_info_from_reduced_model( - joints_name_list - ) - self.NDoF = len(self.joints_list) - self.root_link = root_link - self.g = gravity - ( - self.links_with_inertia, - frames, - self.connecting_joints, - self.tree, - ) = urdf_tree.load_model() + self.model = model + self.NDoF = model.NDoF + self.root_link = self.model.tree.root + self.math = math def crba( self, base_transform: npt.ArrayLike, joint_positions: npt.ArrayLike @@ -55,86 +38,46 @@ def crba( M (npt.ArrayLike): Mass Matrix Jcm (npt.ArrayLike): Centroidal Momentum Matrix """ - Ic = [None] * len(self.tree.links) - X_p = [None] * len(self.tree.links) - Phi = [None] * len(self.tree.links) - M = self.zeros(self.NDoF + 6, self.NDoF + 6) - - for i in range(self.tree.N): - link_i = self.tree.links[i] - link_pi = self.tree.parents[i] - joint_i = self.tree.joints[i] - I, mass, o, rpy = self.extract_link_properties(link_i) - Ic[i] = self.spatial_inertia(I, mass, o, rpy) + model_len = self.model.N + Ic, X_p, Phi = [None] * model_len, [None] * model_len, [None] * model_len + + M = self.math.factory.zeros(self.model.NDoF + 6, self.model.NDoF + 6) + for i, node in enumerate(self.model.tree): + node: Node + link_i, joint_i, link_pi = node.get_elements() + Ic[i] = link_i.spatial_inertia() if link_i.name == self.root_link: # The first "real" link. The joint is universal. - X_p[i] = self.spatial_transform(self.eye(3), self.zeros(3, 1)) - Phi[i] = self.eye(6) - elif joint_i.type == "fixed": - X_J = self.X_fixed_joint(joint_i.origin.xyz, joint_i.origin.rpy) - X_p[i] = X_J - Phi[i] = self.vertcat(0, 0, 0, 0, 0, 0) - elif joint_i.type in ["revolute", "continuous"]: - q = joint_positions[joint_i.idx] if joint_i.idx is not None else 0.0 - X_J = self.X_revolute_joint( - joint_i.origin.xyz, - joint_i.origin.rpy, - joint_i.axis, - q, + X_p[i] = self.math.spatial_transform( + self.math.factory.eye(3), self.math.factory.zeros(3, 1) ) - X_p[i] = X_J - Phi[i] = self.vertcat( - 0, - 0, - 0, - joint_i.axis[0], - joint_i.axis[1], - joint_i.axis[2], - ) - elif joint_i.type in ["prismatic"]: + Phi[i] = self.math.factory.eye(6) + else: q = joint_positions[joint_i.idx] if joint_i.idx is not None else 0.0 - X_J = self.X_prismatic_joint( - joint_i.origin.xyz, - joint_i.origin.rpy, - joint_i.axis, - q, - ) - X_p[i] = X_J - Phi[i] = self.vertcat( - joint_i.axis[0], - joint_i.axis[1], - joint_i.axis[2], - 0, - 0, - 0, - ) - - for i in range(self.tree.N - 1, -1, -1): - link_i = self.tree.links[i] - link_pi = self.tree.parents[i] - joint_i = self.tree.joints[i] - if link_pi.name != self.tree.parents[0].name: - pi = self.tree.links.index(link_pi) + X_p[i] = joint_i.spatial_transform(q=q) + Phi[i] = joint_i.motion_subspace() + + for i, node in reversed(list(enumerate(self.model.tree))): + node: Node + link_i, joint_i, link_pi = node.get_elements() + if link_i.name != self.root_link: + pi = self.model.tree.get_idx_from_name(link_pi.name) Ic[pi] = Ic[pi] + X_p[i].T @ Ic[i] @ X_p[i] F = Ic[i] @ Phi[i] - if joint_i.idx is not None: + if link_i.name != self.root_link and joint_i.idx is not None: M[joint_i.idx + 6, joint_i.idx + 6] = Phi[i].T @ F if link_i.name == self.root_link: M[:6, :6] = Phi[i].T @ F j = i - link_j = self.tree.links[j] - link_pj = self.tree.parents[j] - joint_j = self.tree.joints[j] - while self.tree.parents[j].name != self.tree.parents[0].name: + link_j, joint_j, link_pj = self.model.tree[j].get_elements() + while link_j.name != self.root_link: F = X_p[j].T @ F - j = self.tree.links.index(self.tree.parents[j]) - joint_j = self.tree.joints[j] - if joint_i.name == self.tree.joints[0].name and joint_j.idx is not None: + j = self.model.tree.get_idx_from_name(self.model.tree[j].parent.name) + link_j, joint_j, link_pj = self.model.tree[j].get_elements() + if link_i.name == self.root_link and joint_j.idx is not None: M[:6, joint_j.idx + 6] = F.T @ Phi[j] M[joint_j.idx + 6, :6] = M[:6, joint_j.idx + 6].T - elif ( - joint_j.name == self.tree.joints[0].name and joint_i.idx is not None - ): + elif link_j.name == self.root_link and joint_i.idx is not None: M[joint_i.idx + 6, :6] = F.T @ Phi[j] M[:6, joint_i.idx + 6] = M[joint_i.idx + 6, :6].T elif joint_i.idx is not None and joint_j.idx is not None: @@ -143,41 +86,32 @@ def crba( joint_i.idx + 6, joint_j.idx + 6 ].T - X_G = [None] * len(self.tree.links) - O_X_G = self.eye(6) + X_G = [None] * model_len + O_X_G = self.math.factory.eye(6) O_X_G[:3, 3:] = M[:3, 3:6].T / M[0, 0] - Jcm = self.zeros(6, self.NDoF + 6) - for i in range(self.tree.N): - link_i = self.tree.links[i] - link_pi = self.tree.parents[i] - joint_i = self.tree.joints[i] - if link_pi.name != self.tree.parents[0].name: - pi = self.tree.links.index(link_pi) + Jcm = self.math.factory.zeros(6, self.model.NDoF + 6) + for i, node in enumerate(self.model.tree): + link_i, joint_i, link_pi = node.get_elements() + if link_i.name != self.root_link: + pi = self.model.tree.get_idx_from_name(link_pi.name) pi_X_G = X_G[pi] else: pi_X_G = O_X_G X_G[i] = X_p[i] @ pi_X_G - if link_i.name == self.tree.links[0].name: + if link_i.name == self.root_link: Jcm[:, :6] = X_G[i].T @ Ic[i] @ Phi[i] elif joint_i.idx is not None: Jcm[:, joint_i.idx + 6] = X_G[i].T @ Ic[i] @ Phi[i] # Until now the algorithm returns the joint_position quantities in Body Fixed representation # Moving to mixed representation... - X_to_mixed = self.eye(self.NDoF + 6) + X_to_mixed = self.math.factory.eye(self.model.NDoF + 6) X_to_mixed[:3, :3] = base_transform[:3, :3].T X_to_mixed[3:6, 3:6] = base_transform[:3, :3].T M = X_to_mixed.T @ M @ X_to_mixed Jcm = X_to_mixed[:6, :6].T @ Jcm @ X_to_mixed return M, Jcm - def extract_link_properties(self, link_i): - I = link_i.inertial.inertia - mass = link_i.inertial.mass - o = link_i.inertial.origin.xyz - rpy = link_i.inertial.origin.rpy - return I, mass, o, rpy - def forward_kinematics( self, frame, base_transform: npt.ArrayLike, joint_positions: npt.ArrayLike ) -> npt.ArrayLike: @@ -190,36 +124,13 @@ def forward_kinematics( Returns: T_fk (npt.ArrayLike): The fk represented as Homogenous transformation matrix """ - chain = self.robot_desc.get_chain(self.root_link, frame, links=False) - T_fk = self.eye(4) + chain = self.model.get_joints_chain(self.root_link, frame) + T_fk = self.math.factory.eye(4) T_fk = T_fk @ base_transform - for item in chain: - joint = self.robot_desc.joint_map[item] - if joint.type == "fixed": - xyz = joint.origin.xyz - rpy = joint.origin.rpy - joint_frame = self.H_from_Pos_RPY(xyz, rpy) - T_fk = T_fk @ joint_frame - if joint.type in ["revolute", "continuous"]: - # if the joint is actuated set the value - q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 - T_joint = self.H_revolute_joint( - joint.origin.xyz, - joint.origin.rpy, - joint.axis, - q_, - ) - T_fk = T_fk @ T_joint - elif joint.type in ["prismatic"]: - # if the joint is actuated set the value - q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 - T_joint = self.H_prismatic_joint( - joint.origin.xyz, - joint.origin.rpy, - joint.axis, - q_, - ) - T_fk = T_fk @ T_joint + for joint in chain: + q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 + T_joint = joint.homogeneous(q=q_) + T_fk = T_fk @ T_joint return T_fk def joints_jacobian( @@ -235,47 +146,27 @@ def joints_jacobian( Returns: J (npt.ArrayLike): The Joints Jacobian relative to the frame """ - chain = self.robot_desc.get_chain(self.root_link, frame, links=False) - T_fk = self.eye(4) @ base_transform - J = self.zeros(6, self.NDoF) + chain = self.model.get_joints_chain(self.root_link, frame) + T_fk = self.math.factory.eye(4) @ base_transform + J = self.math.factory.zeros(6, self.NDoF) T_ee = self.forward_kinematics(frame, base_transform, joint_positions) P_ee = T_ee[:3, 3] - for item in chain: - joint = self.robot_desc.joint_map[item] - if joint.type == "fixed": - xyz = joint.origin.xyz - rpy = joint.origin.rpy - joint_frame = self.H_from_Pos_RPY(xyz, rpy) - T_fk = T_fk @ joint_frame + for joint in chain: + q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 + T_joint = joint.homogeneous(q=q_) + T_fk = T_fk @ T_joint if joint.type in ["revolute", "continuous"]: - q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 - T_joint = self.H_revolute_joint( - joint.origin.xyz, - joint.origin.rpy, - joint.axis, - q_, - ) - T_fk = T_fk @ T_joint - p_prev = P_ee - T_fk[:3, 3].array + p_prev = P_ee - T_fk[:3, 3] z_prev = T_fk[:3, :3] @ joint.axis - J_lin = self.skew(z_prev) @ p_prev + J_lin = self.math.skew(z_prev) @ p_prev J_ang = z_prev - - if joint.type in ["prismatic"]: - q_ = joint_positions[joint.idx] if joint.idx is not None else 0.0 - T_joint = self.H_prismatic_joint( - joint.origin.xyz, - joint.origin.rpy, - joint.axis, - q_, - ) - T_fk = T_fk @ T_joint + elif joint.type in ["prismatic"]: z_prev = T_fk[:3, :3] @ joint.axis J_lin = z_prev - J_ang = self.zeros(3) + J_ang = self.math.factory.zeros(3) if joint.idx is not None: - J[:, joint.idx] = self.vertcat(J_lin, J_ang) + J[:, joint.idx] = self.math.vertcat(J_lin, J_ang) return J @@ -285,11 +176,11 @@ def jacobian( J = self.joints_jacobian(frame, base_transform, joint_positions) T_ee = self.forward_kinematics(frame, base_transform, joint_positions) # Adding the floating base part of the Jacobian, in Mixed representation - J_tot = self.zeros(6, self.NDoF + 6) - J_tot[:3, :3] = self.eye(3) - J_tot[:3, 3:6] = -self.skew((T_ee[:3, 3] - base_transform[:3, 3])) + J_tot = self.math.factory.zeros(6, self.NDoF + 6) + J_tot[:3, :3] = self.math.factory.eye(3) + J_tot[:3, 3:6] = -self.math.skew((T_ee[:3, 3] - base_transform[:3, 3])) J_tot[:3, 6:] = J[:3, :] - J_tot[3:, 3:6] = self.eye(3) + J_tot[3:, 3:6] = self.math.factory.eye(3) J_tot[3:, 6:] = J[3:, :] return J_tot @@ -305,7 +196,7 @@ def relative_jacobian( Returns: J (npt.ArrayLike): The Jacobian between the root and the frame """ - base_transform = self.eye(4).array + base_transform = self.math.factory.eye(4) return self.joints_jacobian(frame, base_transform, joint_positions) def CoM_position( @@ -320,18 +211,14 @@ def CoM_position( Returns: com (T): The CoM position """ - com_pos = self.zeros(3, 1) - for item in self.robot_desc.link_map: - link = self.robot_desc.link_map[item] - if link.inertial is not None: - T_fk = self.forward_kinematics(item, base_transform, joint_positions) - T_link = self.H_from_Pos_RPY( - link.inertial.origin.xyz, - link.inertial.origin.rpy, - ) - # Adding the link transform - T_fk = T_fk @ T_link.array - com_pos += T_fk[:3, 3] * link.inertial.mass + com_pos = self.math.factory.zeros(3, 1) + for item in self.model.tree: + link = item.link + T_fk = self.forward_kinematics(link.name, base_transform, joint_positions) + T_link = link.homogeneous() + # Adding the link transform + T_fk = T_fk @ T_link + com_pos += T_fk[:3, 3] * link.inertial.mass com_pos /= self.get_total_mass() return com_pos @@ -341,12 +228,7 @@ def get_total_mass(self): Returns: mass: The total mass """ - mass = 0.0 - for item in self.robot_desc.link_map: - link = self.robot_desc.link_map[item] - if link.inertial is not None: - mass += link.inertial.mass - return mass + return self.model.get_total_mass() def rnea( self, @@ -371,99 +253,65 @@ def rnea( tau (T): generalized force variables """ # TODO: add accelerations - tau = self.zeros(self.NDoF + 6, 1) - Ic = [None] * len(self.tree.links) - X_p = [None] * len(self.tree.links) - Phi = [None] * len(self.tree.links) - v = [None] * len(self.tree.links) - a = [None] * len(self.tree.links) - f = [None] * len(self.tree.links) - - X_to_mixed = self.eye(6) - X_to_mixed[:3, :3] = base_transform[:3, :3].T - X_to_mixed[3:6, 3:6] = base_transform[:3, :3].T + tau = self.math.factory.zeros(self.NDoF + 6, 1) + model_len = self.model.N + + Ic = [None] * model_len + X_p = [None] * model_len + Phi = [None] * model_len + v = [None] * model_len + a = [None] * model_len + f = [None] * model_len - acc_to_mixed = self.zeros(6, 1) + X_to_mixed = self.math.adjoint(base_transform[:3, :3]) + + acc_to_mixed = self.math.factory.zeros(6, 1) acc_to_mixed[:3] = ( - -X_to_mixed[:3, :3] @ self.skew(base_velocity[3:]) @ base_velocity[:3] + -X_to_mixed[:3, :3] @ self.math.skew(base_velocity[3:]) @ base_velocity[:3] ) acc_to_mixed[3:] = ( - -X_to_mixed[:3, :3] @ self.skew(base_velocity[3:]) @ base_velocity[3:] + -X_to_mixed[:3, :3] @ self.math.skew(base_velocity[3:]) @ base_velocity[3:] ) # set initial acceleration (rotated gravity + apparent acceleration) # reshape g as a vertical vector a[0] = -X_to_mixed @ g.reshape(-1, 1) + acc_to_mixed - for i in range(self.tree.N): - link_i = self.tree.links[i] - link_pi = self.tree.parents[i] - joint_i = self.tree.joints[i] - I, mass, o, rpy = self.extract_link_properties(link_i) - Ic[i] = self.spatial_inertia(I, mass, o, rpy) - + # for i in range(self.tree.N): + for i, node in enumerate(self.model.tree): + node: Node + link_i, joint_i, link_pi = node.get_elements() + Ic[i] = link_i.spatial_inertia() if link_i.name == self.root_link: # The first "real" link. The joint is universal. - X_p[i] = self.spatial_transform(self.eye(3), self.zeros(3, 1)) - Phi[i] = self.eye(6) - v_J = Phi[i] @ X_to_mixed @ base_velocity - elif joint_i.type == "fixed": - X_J = self.X_fixed_joint(joint_i.origin.xyz, joint_i.origin.rpy) - X_p[i] = X_J - Phi[i] = self.vertcat(0, 0, 0, 0, 0, 0) - v_J = self.zeros(6, 1) - elif joint_i.type in ["revolute", "continuous"]: - q = joint_positions[joint_i.idx] if joint_i.idx is not None else 0.0 - q_dot = ( - joint_velocities[joint_i.idx] if joint_i.idx is not None else 0.0 - ) - X_J = self.X_revolute_joint( - joint_i.origin.xyz, - joint_i.origin.rpy, - joint_i.axis, - q, - ) - X_p[i] = X_J - Phi[i] = self.vertcat( - 0, 0, 0, joint_i.axis[0], joint_i.axis[1], joint_i.axis[2] + X_p[i] = self.math.spatial_transform( + self.math.factory.eye(3), self.math.factory.zeros(3, 1) ) - v_J = Phi[i] * q_dot - elif joint_i.type in ["prismatic"]: + Phi[i] = self.math.factory.eye(6) + v[i] = X_to_mixed @ base_velocity + a[i] = X_p[i] @ a[0] + else: q = joint_positions[joint_i.idx] if joint_i.idx is not None else 0.0 q_dot = ( joint_velocities[joint_i.idx] if joint_i.idx is not None else 0.0 ) - X_J = self.X_prismatic_joint( - joint_i.origin.xyz, - joint_i.origin.rpy, - joint_i.axis, - q, - ) - X_p[i] = X_J - Phi[i] = self.vertcat( - joint_i.axis[0], joint_i.axis[1], joint_i.axis[2], 0, 0, 0 - ) - v_J = Phi[i] * q_dot - + X_p[i] = joint_i.spatial_transform(q) + Phi[i] = joint_i.motion_subspace() + pi = self.model.tree.get_idx_from_name(link_pi.name) + # pi = self.tree.links.index(link_pi) + v[i] = X_p[i] @ v[pi] + Phi[i] * q_dot + a[i] = X_p[i] @ a[pi] + self.math.spatial_skew(v[i]) @ Phi[i] * q_dot + + f[i] = Ic[i] @ a[i] + self.math.spatial_skew_star(v[i]) @ Ic[i] @ v[i] + + for i, node in reversed(list(enumerate(self.model.tree))): + node: Node + link_i, joint_i, link_pi = node.get_elements() if link_i.name == self.root_link: - v[i] = v_J - a[i] = X_p[i] @ a[0] - else: - pi = self.tree.links.index(link_pi) - v[i] = X_p[i] @ v[pi] + v_J - a[i] = X_p[i] @ a[pi] + self.spatial_skew(v[i]) @ v_J - - f[i] = Ic[i] @ a[i] + self.spatial_skew_star(v[i]) @ Ic[i] @ v[i] - - for i in range(self.tree.N - 1, -1, -1): - joint_i = self.tree.joints[i] - link_i = self.tree.links[i] - link_pi = self.tree.parents[i] - if joint_i.name == self.tree.joints[0].name: tau[:6] = Phi[i].T @ f[i] elif joint_i.idx is not None: tau[joint_i.idx + 6] = Phi[i].T @ f[i] - if link_pi.name != self.tree.parents[0].name: - pi = self.tree.links.index(link_pi) + if link_i.name != self.root_link: + pi = self.model.tree.get_idx_from_name(link_pi.name) f[pi] = f[pi] + X_p[i].T @ f[i] tau[:6] = X_to_mixed.T @ tau[:6] diff --git a/src/adam/core/spatial_math.py b/src/adam/core/spatial_math.py index 2706d65a..296ab0dd 100644 --- a/src/adam/core/spatial_math.py +++ b/src/adam/core/spatial_math.py @@ -1,14 +1,74 @@ import abc -import numpy as np import numpy.typing as npt class ArrayLike(abc.ABC): """Abstract class for a generic Array wrapper. Every method should be implemented for every data type.""" + """This class has to implemented the following operators: """ + + @abc.abstractmethod + def __add__(self, other): + pass + + @abc.abstractmethod + def __radd__(self, other): + pass + + @abc.abstractmethod + def __sub__(self, other): + pass + + @abc.abstractmethod + def __rsub__(self, other): + pass + + @abc.abstractmethod + def __mul__(self, other): + pass + + @abc.abstractmethod + def __rmul__(self, other): + pass + + @abc.abstractmethod + def __matmul__(self, other): + pass + + @abc.abstractmethod + def __rmatmul__(self, other): + pass + @abc.abstractmethod - def zeros(x: npt.ArrayLike) -> npt.ArrayLike: + def __neg__(self): + pass + + @abc.abstractmethod + def __getitem__(self, item): + pass + + @abc.abstractmethod + def __setitem__(self, key, value): + pass + + @abc.abstractmethod + def __truediv__(self, other): + pass + + @abc.abstractproperty + def T(self): + """ + Returns: Transpose of the array + """ + pass + + +class ArrayLikeFactory(abc.ABC): + """Abstract class for a generic Array wrapper. Every method should be implemented for every data type.""" + + @abc.abstractmethod + def zeros(self, x: npt.ArrayLike) -> npt.ArrayLike: """ Args: x (npt.ArrayLike): matrix dimension @@ -19,24 +79,40 @@ def zeros(x: npt.ArrayLike) -> npt.ArrayLike: pass @abc.abstractmethod - def vertcat(x: npt.ArrayLike) -> npt.ArrayLike: + def eye(self, x: npt.ArrayLike) -> npt.ArrayLike: """ Args: - x (npt.ArrayLike): elements + x (npt.ArrayLike): matrix dimension Returns: - npt.ArrayLike: vertical concatenation of elements x + npt.ArrayLike: identity matrix of dimension x """ pass + +class SpatialMath: + """Class implementing the main geometric functions used for computing rigid-body algorithm + + Args: + ArrayLike: abstract class describing a generic Array wrapper. It needs to be implemented for every data type + + """ + + def __init__(self, factory: ArrayLikeFactory): + self._factory = factory + + @property + def factory(self) -> ArrayLikeFactory: + return self._factory + @abc.abstractmethod - def eye(x: npt.ArrayLike) -> npt.ArrayLike: + def vertcat(x: npt.ArrayLike) -> npt.ArrayLike: """ Args: - x (npt.ArrayLike): matrix dimension + x (npt.ArrayLike): elements Returns: - npt.ArrayLike: identity matrix of dimension x + npt.ArrayLike: vertical concatenation of elements x """ pass @@ -62,17 +138,11 @@ def cos(x: npt.ArrayLike) -> npt.ArrayLike: """ pass + @abc.abstractmethod + def skew(x): + pass -class SpatialMath(ArrayLike): - """Class implementing the main geometric functions used for computing rigid-body algorithm - - Args: - ArrayLike: abstract class describing a generic Array wrapper. It needs to be implemented for every data type - - """ - - @classmethod - def R_from_axis_angle(cls, axis: npt.ArrayLike, q: npt.ArrayLike) -> npt.ArrayLike: + def R_from_axis_angle(self, axis: npt.ArrayLike, q: npt.ArrayLike) -> npt.ArrayLike: """ Args: axis (npt.ArrayLike): axis vector @@ -81,15 +151,14 @@ def R_from_axis_angle(cls, axis: npt.ArrayLike, q: npt.ArrayLike) -> npt.ArrayLi Returns: npt.ArrayLike: rotation matrix from axis-angle representation """ - cq, sq = cls.cos(q), cls.sin(q) + cq, sq = self.cos(q), self.sin(q) return ( - cq * (cls.eye(3) - cls.outer(axis, axis)) - + sq * cls.skew(axis) - + cls.outer(axis, axis) + cq * (self.factory.eye(3) - self.outer(axis, axis)) + + sq * self.skew(axis) + + self.outer(axis, axis) ) - @classmethod - def Rx(cls, q: npt.ArrayLike) -> npt.ArrayLike: + def Rx(self, q: npt.ArrayLike) -> npt.ArrayLike: """ Args: q (npt.ArrayLike): angle value @@ -97,16 +166,15 @@ def Rx(cls, q: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: rotation matrix around x axis """ - R = cls.eye(3) - cq, sq = cls.cos(q), cls.sin(q) + R = self.factory.eye(3) + cq, sq = self.cos(q), self.sin(q) R[1, 1] = cq R[1, 2] = -sq R[2, 1] = sq R[2, 2] = cq return R - @classmethod - def Ry(cls, q: npt.ArrayLike) -> npt.ArrayLike: + def Ry(self, q: npt.ArrayLike) -> npt.ArrayLike: """ Args: q (npt.ArrayLike): angle value @@ -114,16 +182,15 @@ def Ry(cls, q: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: rotation matrix around y axis """ - R = cls.eye(3) - cq, sq = cls.cos(q), cls.sin(q) + R = self.factory.eye(3) + cq, sq = self.cos(q), self.sin(q) R[0, 0] = cq R[0, 2] = sq R[2, 0] = -sq R[2, 2] = cq return R - @classmethod - def Rz(cls, q: npt.ArrayLike) -> npt.ArrayLike: + def Rz(self, q: npt.ArrayLike) -> npt.ArrayLike: """ Args: q (npt.ArrayLike): angle value @@ -131,17 +198,16 @@ def Rz(cls, q: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: rotation matrix around z axis """ - R = cls.eye(3) - cq, sq = cls.cos(q), cls.sin(q) + R = self.factory.eye(3) + cq, sq = self.cos(q), self.sin(q) R[0, 0] = cq R[0, 1] = -sq R[1, 0] = sq R[1, 1] = cq return R - @classmethod def H_revolute_joint( - cls, + self, xyz: npt.ArrayLike, rpy: npt.ArrayLike, axis: npt.ArrayLike, @@ -157,15 +223,14 @@ def H_revolute_joint( Returns: npt.ArrayLike: Homogeneous transform """ - T = cls.eye(4) - R = cls.R_from_RPY(rpy) @ cls.R_from_axis_angle(axis, q) + T = self.factory.eye(4) + R = self.R_from_RPY(rpy) @ self.R_from_axis_angle(axis, q) T[:3, :3] = R T[:3, 3] = xyz return T - @classmethod def H_prismatic_joint( - cls, + self, xyz: npt.ArrayLike, rpy: npt.ArrayLike, axis: npt.ArrayLike, @@ -181,14 +246,13 @@ def H_prismatic_joint( Returns: npt.ArrayLike: Homogeneous transform """ - T = cls.eye(4) - R = cls.R_from_RPY(rpy) + T = self.factory.eye(4) + R = self.R_from_RPY(rpy) T[:3, :3] = R - T[:3, 3] = xyz + q * cls.array(axis) + T[:3, 3] = xyz + q * self.factory.array(axis) return T - @classmethod - def H_from_Pos_RPY(cls, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike: + def H_from_Pos_RPY(self, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike: """ Args: xyz (npt.ArrayLike): translation vector @@ -197,13 +261,12 @@ def H_from_Pos_RPY(cls, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike Returns: npt.ArrayLike: Homegeneous transform """ - T = cls.eye(4) - T[:3, :3] = cls.R_from_RPY(rpy) + T = self.factory.eye(4) + T[:3, :3] = self.R_from_RPY(rpy) T[:3, 3] = xyz return T - @classmethod - def R_from_RPY(cls, rpy: npt.ArrayLike) -> npt.ArrayLike: + def R_from_RPY(self, rpy: npt.ArrayLike) -> npt.ArrayLike: """ Args: rpy (npt.ArrayLike): rotation as rpy angles @@ -211,11 +274,10 @@ def R_from_RPY(cls, rpy: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: Rotation matrix """ - return cls.Rz(rpy[2]) @ cls.Ry(rpy[1]) @ cls.Rx(rpy[0]) + return self.Rz(rpy[2]) @ self.Ry(rpy[1]) @ self.Rx(rpy[0]) - @classmethod def X_revolute_joint( - cls, + self, xyz: npt.ArrayLike, rpy: npt.ArrayLike, axis: npt.ArrayLike, @@ -232,14 +294,13 @@ def X_revolute_joint( npt.ArrayLike: Spatial transform of a revolute joint given its rotation angle """ # TODO: give Featherstone reference - T = cls.H_revolute_joint(xyz, rpy, axis, q) + T = self.H_revolute_joint(xyz, rpy, axis, q) R = T[:3, :3].T p = -T[:3, :3].T @ T[:3, 3] - return cls.spatial_transform(R, p) + return self.spatial_transform(R, p) - @classmethod def X_prismatic_joint( - cls, + self, xyz: npt.ArrayLike, rpy: npt.ArrayLike, axis: npt.ArrayLike, @@ -255,13 +316,12 @@ def X_prismatic_joint( Returns: npt.ArrayLike: Spatial transform of a prismatic joint given its increment """ - T = cls.H_prismatic_joint(xyz, rpy, axis, q) + T = self.H_prismatic_joint(xyz, rpy, axis, q) R = T[:3, :3].T p = -T[:3, :3].T @ T[:3, 3] - return cls.spatial_transform(R, p) + return self.spatial_transform(R, p) - @classmethod - def X_fixed_joint(cls, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike: + def X_fixed_joint(self, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike: """ Args: xyz (npt.ArrayLike): joint origin in the urdf @@ -270,15 +330,13 @@ def X_fixed_joint(cls, xyz: npt.ArrayLike, rpy: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: Spatial transform of a fixed joint """ - T = cls.H_from_Pos_RPY(xyz, rpy) + T = self.H_from_Pos_RPY(xyz, rpy) R = T[:3, :3].T p = -T[:3, :3].T @ T[:3, 3] - return cls.spatial_transform(R, p) - - @classmethod - def spatial_transform(cls, R: npt.ArrayLike, p: npt.ArrayLike) -> npt.ArrayLike: - """_summary_ + return self.spatial_transform(R, p) + def spatial_transform(self, R: npt.ArrayLike, p: npt.ArrayLike) -> npt.ArrayLike: + """ Args: R (npt.ArrayLike): Rotation matrix p (npt.ArrayLike): translation vector @@ -286,15 +344,18 @@ def spatial_transform(cls, R: npt.ArrayLike, p: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: spatial transform """ - X = cls.zeros(6, 6) + X = self.factory.zeros(6, 6) X[:3, :3] = R X[3:, 3:] = R - X[:3, 3:] = cls.skew(p) @ R + X[:3, 3:] = self.skew(p) @ R return X - @classmethod def spatial_inertia( - cls, I: npt.ArrayLike, mass: npt.ArrayLike, c: npt.ArrayLike, rpy: npt.ArrayLike + self, + I: npt.ArrayLike, + mass: npt.ArrayLike, + c: npt.ArrayLike, + rpy: npt.ArrayLike, ) -> npt.ArrayLike: """ Args: @@ -306,21 +367,20 @@ def spatial_inertia( Returns: npt.ArrayLike: the 6x6 inertia matrix expressed at the origin of the link (with rotation) """ - IO = cls.zeros(6, 6) - Sc = cls.skew(c) - R = cls.R_from_RPY(rpy) - inertia_matrix = cls.array( + IO = self.factory.zeros(6, 6) + Sc = self.skew(c) + R = self.R_from_RPY(rpy) + inertia_matrix = self.factory.array( [[I.ixx, I.ixy, I.ixz], [I.ixy, I.iyy, I.iyz], [I.ixz, I.iyz, I.izz]] ) IO[3:, 3:] = R @ inertia_matrix @ R.T + mass * Sc @ Sc.T IO[3:, :3] = mass * Sc IO[:3, 3:] = mass * Sc.T - IO[:3, :3] = cls.eye(3) * mass + IO[:3, :3] = self.factory.eye(3) * mass return IO - @classmethod - def spatial_skew(cls, v: npt.ArrayLike) -> npt.ArrayLike: + def spatial_skew(self, v: npt.ArrayLike) -> npt.ArrayLike: """ Args: v (npt.ArrayLike): 6D vector @@ -328,14 +388,13 @@ def spatial_skew(cls, v: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: spatial skew matrix """ - X = cls.zeros(6, 6) - X[:3, :3] = cls.skew(v[3:]) - X[:3, 3:] = cls.skew(v[:3]) - X[3:, 3:] = cls.skew(v[3:]) + X = self.factory.zeros(6, 6) + X[:3, :3] = self.skew(v[3:]) + X[:3, 3:] = self.skew(v[:3]) + X[3:, 3:] = self.skew(v[3:]) return X - @classmethod - def spatial_skew_star(cls, v: npt.ArrayLike) -> npt.ArrayLike: + def spatial_skew_star(self, v: npt.ArrayLike) -> npt.ArrayLike: """ Args: v (npt.ArrayLike): 6D vector @@ -343,4 +402,16 @@ def spatial_skew_star(cls, v: npt.ArrayLike) -> npt.ArrayLike: Returns: npt.ArrayLike: negative spatial skew matrix traspose """ - return -cls.spatial_skew(v).T + return -self.spatial_skew(v).T + + def adjoint(self, R: npt.ArrayLike) -> npt.ArrayLike: + """ + Args: + R (npt.ArrayLike): Rotation matrix + Returns: + npt.ArrayLike: adjoint matrix + """ + X = self.factory.eye(6) + X[:3, :3] = R.T + X[3:6, 3:6] = R.T + return X diff --git a/src/adam/core/urdf_tree.py b/src/adam/core/urdf_tree.py deleted file mode 100644 index 9622a667..00000000 --- a/src/adam/core/urdf_tree.py +++ /dev/null @@ -1,146 +0,0 @@ -# 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. - -import contextlib -import logging -from dataclasses import dataclass, field -from os import error -from typing import List - -from prettytable import PrettyTable -from urdf_parser_py.urdf import URDF - - -@dataclass -class Tree: - joints: List[str] = field(default_factory=list) - links: List[str] = field(default_factory=list) - parents: List[str] = field(default_factory=list) - N: int = None - - -@dataclass -class Element: - name: str - idx: int = None - - -class URDFTree: - """This class builds the branched tree graph from a given urdf and the list of joints""" - - joint_types = ["prismatic", "revolute", "continuous"] - - def __init__( - self, - urdfstring: str, - joints_name_list: list, - root_link: str = "root_link", - ) -> None: - """ - Args: - urdfstring (str): path of the urdf - joints_name_list (list): list of the actuated joints - root_link (str, optional): the first link. Defaults to 'root_link'. - """ - self.robot_desc = URDF.from_xml_file(urdfstring) - self.joints_list = self.get_joints_info_from_reduced_model(joints_name_list) - self.NDoF = len(self.joints_list) - self.root_link = root_link - - def get_joints_info_from_reduced_model(self, joints_name_list: list) -> list: - joints_list = [] - for item in self.robot_desc.joint_map: - self.robot_desc.joint_map[item].idx = None - - for [idx, joint_str] in enumerate(joints_name_list): - # adding the field idx to the reduced joint list - self.robot_desc.joint_map[joint_str].idx = idx - joints_list += [self.robot_desc.joint_map[joint_str]] - if len(joints_list) != len(joints_name_list): - raise error("Some joints are not in the URDF") - return joints_list - - def load_model(self): - """This function computes the branched tree graph. - - Returns: - The list of links, frames, the connecting joints and the tree. - It also prints the urdf elements. - """ - links = [] - frames = [] - joints = [] - tree = Tree() - # If the link does not have inertia is considered a frame - for item in self.robot_desc.link_map: - if self.robot_desc.link_map[item].inertial is not None: - links += [item] - else: - frames += [item] - - table_links = PrettyTable(["Idx", "Link name"]) - table_links.title = "Links" - for [i, item] in enumerate(links): - table_links.add_row([i, item]) - logging.debug(table_links) - table_frames = PrettyTable(["Idx", "Frame name", "Parent"]) - table_frames.title = "Frames" - for [i, item] in enumerate(frames): - with contextlib.suppress(Exception): - table_frames.add_row( - [ - i, - item, - self.robot_desc.parent_map[item][1], - ] - ) - logging.debug(table_frames) - """The node 0 contains the 1st link, the fictitious joint that connects the root the the world - and the world""" - tree.links.append(self.robot_desc.link_map[self.root_link]) - joint_0 = Element("fictitious_joint") - tree.joints.append(joint_0) - parent_0 = Element("world_link") - tree.parents.append(parent_0) - - table_joints = PrettyTable(["Idx", "Joint name", "Type", "Parent", "Child"]) - table_joints.title = "Joints" - - # Cicling on the joints. I need to check that the tree order is correct. - # An element in the parent list should be already present in the link list. If not, no element is added to the tree. - # If a joint is already in the list of joints, no element is added to the tree. - i = 1 - for _ in self.robot_desc.joint_map: - for item in self.robot_desc.joint_map: - parent = self.robot_desc.joint_map[item].parent - child = self.robot_desc.joint_map[item].child - if ( - self.robot_desc.link_map[parent] - in tree.links # this line preserves the order in the tree - and self.robot_desc.joint_map[item] - not in tree.joints # if the joint is present in the list of joints, no element is added - and self.robot_desc.link_map[child].inertial - is not None # if the child is a frame (massless link), no element is added - ): - joints += [item] - table_joints.add_row( - [ - i, - item, - self.robot_desc.joint_map[item].type, - parent, - child, - ] - ) - i += 1 - tree.joints.append(self.robot_desc.joint_map[item]) - tree.links.append( - self.robot_desc.link_map[self.robot_desc.joint_map[item].child] - ) - tree.parents.append( - self.robot_desc.link_map[self.robot_desc.joint_map[item].parent] - ) - tree.N = len(tree.links) - logging.debug(table_joints) - return links, frames, joints, tree diff --git a/src/adam/jax/__init__.py b/src/adam/jax/__init__.py index c42c5cb8..70be81d8 100644 --- a/src/adam/jax/__init__.py +++ b/src/adam/jax/__init__.py @@ -3,3 +3,4 @@ # GNU Lesser General Public License v2.1 or any later version. from .computations import KinDynComputations +from .jax_like import JaxLike diff --git a/src/adam/jax/computations.py b/src/adam/jax/computations.py index f5174ad0..eaf64407 100644 --- a/src/adam/jax/computations.py +++ b/src/adam/jax/computations.py @@ -7,10 +7,11 @@ from jax import grad, jit, vmap from adam.core.rbd_algorithms import RBDAlgorithms -from adam.jax.jax_like import JaxLike +from adam.jax.jax_like import SpatialMath +from adam.model import Model, URDFModelFactory -class KinDynComputations(RBDAlgorithms, JaxLike): +class KinDynComputations: """This is a small class that retrieves robot quantities using Jax in mixed representation, for Floating Base systems - as humanoid robots. """ @@ -28,12 +29,12 @@ def __init__( joints_name_list (list): list of the actuated joints root_link (str, optional): the first link. Defaults to 'root_link'. """ - super().__init__( - urdfstring=urdfstring, - joints_name_list=joints_name_list, - root_link=root_link, - gravity=gravity, - ) + math = SpatialMath() + factory = URDFModelFactory(path=urdfstring, math=math) + model = Model.build(factory=factory, joints_name_list=joints_name_list) + self.rbdalgos = RBDAlgorithms(model=model, math=math) + self.NDoF = self.rbdalgos.NDoF + self.g = gravity def mass_matrix(self, base_transform: jnp.array, joint_positions: jnp.array): """Returns the Mass Matrix functions computed the CRBA @@ -45,7 +46,7 @@ def mass_matrix(self, base_transform: jnp.array, joint_positions: jnp.array): Returns: M (jax): Mass Matrix """ - [M, _] = super().crba(base_transform, joint_positions) + [M, _] = self.rbdalgos.crba(base_transform, joint_positions) return M.array def centroidal_momentum_matrix( @@ -60,7 +61,7 @@ def centroidal_momentum_matrix( Returns: Jcc (jnp.array): Centroidal Momentum matrix """ - [_, Jcm] = self.crba(base_transform, joint_positions) + [_, Jcm] = self.rbdalgos.crba(base_transform, joint_positions) return Jcm.array def relative_jacobian(self, frame: str, joint_positions: jnp.array): @@ -73,7 +74,7 @@ def relative_jacobian(self, frame: str, joint_positions: jnp.array): Returns: J (jnp.array): The Jacobian between the root and the frame """ - return super().relative_jacobian(frame, joint_positions).array + return self.rbdalgos.relative_jacobian(frame, joint_positions).array def forward_kinematics( self, frame: str, base_transform: jnp.array, joint_positions: jnp.array @@ -88,7 +89,9 @@ def forward_kinematics( Returns: T_fk (jnp.array): The fk represented as Homogenous transformation matrix """ - return super().forward_kinematics(frame, base_transform, joint_positions).array + return self.rbdalgos.forward_kinematics( + frame, base_transform, joint_positions + ).array def forward_kinematics_fun(self, frame): return lambda T, joint_positions: self.forward_kinematics( @@ -106,7 +109,7 @@ def jacobian(self, frame: str, base_transform, joint_positions): Returns: J_tot (jnp.array): The Jacobian relative to the frame """ - return super().jacobian(frame, base_transform, joint_positions).array + return self.rbdalgos.jacobian(frame, base_transform, joint_positions).array def bias_force( self, @@ -127,11 +130,9 @@ def bias_force( Returns: h (jnp.array): the bias force """ - return ( - super() - .rnea(base_transform, joint_positions, base_velocity, s_dot, self.g) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, joint_positions, base_velocity, s_dot, self.g + ).array.squeeze() def coriolis_term( self, @@ -152,17 +153,13 @@ def coriolis_term( Returns: C (jnp.array): the Coriolis term """ - return ( - super() - .rnea( - base_transform, - joint_positions, - base_velocity.reshape(6, 1), - s_dot, - np.zeros(6), - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + base_velocity.reshape(6, 1), + s_dot, + np.zeros(6), + ).array.squeeze() def gravity_term( self, base_transform: jnp.array, joint_positions: jnp.array @@ -177,17 +174,13 @@ def gravity_term( Returns: G (jnp.array): the gravity term """ - return ( - super() - .rnea( - base_transform, - joint_positions, - np.zeros(6).reshape(6, 1), - np.zeros(self.NDoF), - self.g, - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + np.zeros(6).reshape(6, 1), + np.zeros(self.NDoF), + self.g, + ).array.squeeze() def CoM_position( self, base_transform: jnp.array, joint_positions: jnp.array @@ -201,4 +194,14 @@ def CoM_position( Returns: com (jnp.array): The CoM position """ - return super().CoM_position(base_transform, joint_positions).array.squeeze() + return self.rbdalgos.CoM_position( + base_transform, joint_positions + ).array.squeeze() + + def get_total_mass(self) -> float: + """Returns the total mass of the robot + + Returns: + mass: The total mass + """ + return self.rbdalgos.get_total_mass() diff --git a/src/adam/jax/jax_like.py b/src/adam/jax/jax_like.py index f6cd2fd6..1a2a7982 100644 --- a/src/adam/jax/jax_like.py +++ b/src/adam/jax/jax_like.py @@ -8,7 +8,8 @@ import jax.numpy as jnp import numpy.typing as npt -from adam.core.spatial_math import ArrayLike +from adam.core.spatial_math import ArrayLike, ArrayLikeFactory, SpatialMath +from adam.numpy import NumpyLike @dataclass @@ -20,11 +21,9 @@ class JaxLike(ArrayLike): def __setitem__(self, idx, value: Union["JaxLike", npt.ArrayLike]): """Overrides set item operator""" if type(self) is type(value): - value.array = jnp.squeeze(value.array) - try: - self.array = self.array.at[idx].set(value.array) - except: - self.array = self.array.at[idx].set(value.array.reshape(-1, 1)) + self.array = self.array.at[idx].set( + value.array.reshape(self.array[idx].shape) + ) else: self.array = self.array.at[idx].set(value) @@ -49,15 +48,17 @@ def T(self) -> "JaxLike": def __matmul__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": """Overrides @ operator""" - if type(self) is not type(other): + if type(other) in [JaxLike, NumpyLike]: + return JaxLike(self.array @ other.array) + else: return JaxLike(self.array @ jnp.array(other)) - return JaxLike(self.array @ other.array) def __rmatmul__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": """Overrides @ operator""" - if type(self) is not type(other): - return JaxLike(jnp.array(other) @ self.array) - return JaxLike(other.array @ self.array) + if type(other) in [JaxLike, NumpyLike]: + return JaxLike(other.array * self.array) + else: + return JaxLike(jnp.array(other) * self.array) def __mul__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": """Overrides * operator""" @@ -91,6 +92,7 @@ def __radd__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": def __sub__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": """Overrides - operator""" + if type(self) is not type(other): return JaxLike(self.array.squeeze() - other.squeeze()) return JaxLike(self.array.squeeze() - other.array.squeeze()) @@ -98,13 +100,15 @@ def __sub__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": def __rsub__(self, other: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": """Overrides - operator""" if type(self) is not type(other): - return JaxLike(self.array.squeeze() - other.squeeze()) - return JaxLike(self.array.squeeze() - other.array.squeeze()) + return JaxLike(other.squeeze() - self.array.squeeze()) + return JaxLike(other.array.squeeze() - self.array.squeeze()) def __neg__(self) -> "JaxLike": """Overrides - operator""" return JaxLike(-self.array) + +class JaxLikeFactory(ArrayLikeFactory): @staticmethod def zeros(*x) -> "JaxLike": """ @@ -113,18 +117,6 @@ def zeros(*x) -> "JaxLike": """ return JaxLike(jnp.zeros(x)) - @staticmethod - def vertcat(*x) -> "JaxLike": - """ - Returns: - JaxLike: Vertical concatenation of elements - """ - if isinstance(x[0], JaxLike): - v = jnp.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) - else: - v = jnp.vstack([x[i] for i in range(len(x))]).reshape(-1, 1) - return JaxLike(v) - @staticmethod def eye(x) -> "JaxLike": """ @@ -133,20 +125,6 @@ def eye(x) -> "JaxLike": """ return JaxLike(jnp.eye(x)) - @staticmethod - def skew(x: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": - """ - Args: - x (Union[JaxLike, npt.ArrayLike]): vector - - Returns: - JaxLike: the skew symmetric matrix from x - """ - if not isinstance(x, JaxLike): - return -jnp.cross(jnp.array(x), jnp.eye(3), axisa=0, axisb=0) - x = x.array - return JaxLike(-jnp.cross(jnp.array(x), jnp.eye(3), axisa=0, axisb=0)) - @staticmethod def array(*x) -> "JaxLike": """ @@ -155,6 +133,11 @@ def array(*x) -> "JaxLike": """ return JaxLike(jnp.array(x)) + +class SpatialMath(SpatialMath): + def __init__(self): + super().__init__(JaxLikeFactory()) + @staticmethod def sin(x: npt.ArrayLike) -> "JaxLike": """ @@ -190,3 +173,29 @@ def outer(x: npt.ArrayLike, y: npt.ArrayLike) -> "JaxLike": x = jnp.array(x) y = jnp.array(y) return JaxLike(jnp.outer(x, y)) + + @staticmethod + def skew(x: Union["JaxLike", npt.ArrayLike]) -> "JaxLike": + """ + Args: + x (Union[JaxLike, npt.ArrayLike]): vector + + Returns: + JaxLike: the skew symmetric matrix from x + """ + if not isinstance(x, JaxLike): + return -jnp.cross(jnp.array(x), jnp.eye(3), axisa=0, axisb=0) + x = x.array + return JaxLike(-jnp.cross(jnp.array(x), jnp.eye(3), axisa=0, axisb=0)) + + @staticmethod + def vertcat(*x) -> "JaxLike": + """ + Returns: + JaxLike: Vertical concatenation of elements + """ + if isinstance(x[0], JaxLike): + v = jnp.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) + else: + v = jnp.vstack([x[i] for i in range(len(x))]).reshape(-1, 1) + return JaxLike(v) diff --git a/src/adam/model/__init__.py b/src/adam/model/__init__.py new file mode 100644 index 00000000..0dd4bf9e --- /dev/null +++ b/src/adam/model/__init__.py @@ -0,0 +1,6 @@ +from .abc_factories import Joint, Link, ModelFactory +from .model import Model +from .std_factories.std_joint import StdJoint +from .std_factories.std_link import StdLink +from .std_factories.std_model import URDFModelFactory +from .tree import Node, Tree diff --git a/src/adam/model/abc_factories.py b/src/adam/model/abc_factories.py new file mode 100644 index 00000000..9e406026 --- /dev/null +++ b/src/adam/model/abc_factories.py @@ -0,0 +1,147 @@ +import abc +import dataclasses +from typing import List + +import numpy.typing as npt + +from adam.core.spatial_math import SpatialMath + + +@dataclasses.dataclass +class Joint(abc.ABC): + """Base Joint class. You need to fill at least these fields""" + + math: SpatialMath + name: str + parent: str + child: str + type: str + axis: List + origin: List + limit: List + idx: int + """ + Abstract base class for all joints. + """ + + @abc.abstractmethod + def spatial_transform(self, q: npt.ArrayLike) -> npt.ArrayLike: + """ + Args: + q (npt.ArrayLike): joint motion + + Returns: + npt.ArrayLike: spatial transform of the joint given q + """ + pass + + @abc.abstractmethod + def motion_subspace(self) -> npt.ArrayLike: + """ + Returns: + npt.ArrayLike: motion subspace of the joint + """ + + @abc.abstractmethod + def homogeneous(self, q: npt.ArrayLike) -> npt.ArrayLike: + """ + Args: + q (npt.ArrayLike): joint value + Returns: + npt.ArrayLike: homogeneous transform given the joint value + """ + pass + + +@dataclasses.dataclass +class Inertial: + """Inertial description""" + + mass: npt.ArrayLike + inertia = npt.ArrayLike + origin = npt.ArrayLike + + +@dataclasses.dataclass +class Link(abc.ABC): + """Base Link class. You need to fill at least these fields""" + + math: SpatialMath + name: str + visuals: List + inertial: Inertial + collisions: List + origin: List + + @abc.abstractmethod + def spatial_inertia(self) -> npt.ArrayLike: + """ + Args: + link (Link): Link + + Returns: + npt.ArrayLike: the 6x6 inertia matrix expressed at the origin of the link (with rotation) + """ + pass + + @abc.abstractmethod + def homogeneous(self) -> npt.ArrayLike: + """ + Returns: + npt.ArrayLike: the homogeneus transform of the link + """ + pass + + +@dataclasses.dataclass +class ModelFactory(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: SpatialMath + name: str + + @abc.abstractmethod + def build_link(self) -> Link: + """build the single link + Returns: + Link + """ + pass + + @abc.abstractmethod + def build_joint(self) -> Joint: + """build the single joint + + Returns: + Joint + """ + pass + + @abc.abstractmethod + def get_links(self) -> List[Link]: + """ + Returns: + List[Link]: the list of the link + """ + pass + + @abc.abstractmethod + def get_frames(self) -> List[Link]: + """ + Returns: + List[Link]: the list of the frames + """ + pass + + @abc.abstractmethod + def get_joints(self) -> List[Joint]: + """ + Returns: + List[Joint]: the list of the joints + """ + pass diff --git a/src/adam/model/model.py b/src/adam/model/model.py new file mode 100644 index 00000000..9c1d5afe --- /dev/null +++ b/src/adam/model/model.py @@ -0,0 +1,144 @@ +import dataclasses +import pathlib +from typing import Dict, List + +from adam.model.abc_factories import Joint, Link, ModelFactory +from adam.model.tree import Tree + + +@dataclasses.dataclass +class Model: + """ + Model class. It describes the robot using links and frames and their connectivity""" + + name: str + links: List[Link] + frames: List[Link] + joints: List[Joint] + tree: Tree + NDoF: int + + 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]) -> "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 + + Returns: + Model: the model describing the robot + """ + + joints = factory.get_joints() + links = factory.get_links() + frames = factory.get_frames() + + # set idx to the actuated joints + for [idx, joint_str] in enumerate(joints_name_list): + for joint in joints: + if joint.name == joint_str: + joint.idx = idx + + tree = Tree.build_tree(links=links, joints=joints) + + # generate some useful dict + joints: Dict(str, Joint) = {joint.name: joint for joint in joints} + links: Dict(str, Link) = {link.name: link for link in links} + frames: Dict(str, Link) = {frame.name: frame for frame in frames} + + return Model( + name=factory.name, + links=links, + frames=frames, + joints=joints, + tree=tree, + NDoF=len(joints_name_list), + ) + + 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 + """ + + if target not in list(self.links) and target not in list(self.frames): + raise ValueError(f"{target} is not not in the robot model.") + + if target == root: + return [] + chain = [] + current_node = [ + joint for joint in self.joints.values() if joint.child == target + ][0] + + chain.insert(0, current_node) + while current_node.parent != root: + current_node = [ + joint + for joint in self.joints.values() + if joint.child == current_node.parent + ][0] + chain.insert(0, current_node) + return chain + + def get_total_mass(self) -> float: + """total mass of the robot + + Returns: + float: the total mass of the robot + """ + mass = 0.0 + for item in self.links: + link = self.links[item] + mass += link.inertial.mass + return mass + + def get_ordered_link_list(self): + """get the ordered list of the link, based on the direction of the graph + + Returns: + list: ordered link list + """ + return self.tree.get_ordered_nodes_list() + + def print_table(self): + """print the table that describes the connectivity between the elements. + You need rich to use it + """ + try: + from rich.console import Console + from rich.table import Table + except Exception: + print("rich is not installed!") + return + + console = Console() + + console = Console() + table = Table(show_header=True, header_style="bold red") + table.add_column("Idx") + table.add_column("Parent Link") + table.add_column("Joint name") + table.add_column("Child Link") + table.add_column("Type") + + nodes = self.tree.graph + + j = 1 + for item in nodes: + if len(nodes[item].children) != 0: + for arc in nodes[item].arcs: + table.add_row(str(j), item, arc.name, arc.child, arc.type) + j += 1 + + console.print(table) diff --git a/src/adam/model/std_factories/__init__.py b/src/adam/model/std_factories/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/src/adam/model/std_factories/std_joint.py b/src/adam/model/std_factories/std_joint.py new file mode 100644 index 00000000..a72787d8 --- /dev/null +++ b/src/adam/model/std_factories/std_joint.py @@ -0,0 +1,106 @@ +from typing import Union + +import numpy.typing as npt +import urdf_parser_py.urdf + +from adam.core.spatial_math import SpatialMath +from adam.model import Joint + + +class StdJoint(Joint): + """Standard Joint class""" + + def __init__( + self, + joint: urdf_parser_py.urdf.Joint, + math: SpatialMath, + idx: Union[int, None] = None, + ) -> None: + self.math = math + self.name = joint.name + self.parent = joint.parent + self.child = joint.child + self.type = joint.joint_type + self.axis = joint.axis + self.origin = joint.origin + self.limit = joint.limit + self.idx = idx + + def homogeneous(self, q: npt.ArrayLike) -> npt.ArrayLike: + """ + Args: + q (npt.ArrayLike): joint value + + Returns: + npt.ArrayLike: the homogenous transform of a joint, given q + """ + + if self.type == "fixed": + xyz = self.origin.xyz + rpy = self.origin.rpy + return self.math.H_from_Pos_RPY(xyz, rpy) + elif self.type in ["revolute", "continuous"]: + return self.math.H_revolute_joint( + self.origin.xyz, + self.origin.rpy, + self.axis, + q, + ) + elif self.type in ["prismatic"]: + return self.math.H_prismatic_joint( + self.origin.xyz, + self.origin.rpy, + self.axis, + q, + ) + + def spatial_transform(self, q: npt.ArrayLike) -> npt.ArrayLike: + """ + Args: + q (npt.ArrayLike): joint motion + + Returns: + npt.ArrayLike: spatial transform of the joint given q + """ + if self.type == "fixed": + return self.math.X_fixed_joint(self.origin.xyz, self.origin.rpy) + elif self.type in ["revolute", "continuous"]: + return self.math.X_revolute_joint( + self.origin.xyz, self.origin.rpy, self.axis, q + ) + elif self.type in ["prismatic"]: + return self.math.X_prismatic_joint( + self.origin.xyz, + self.origin.rpy, + self.axis, + q, + ) + + def motion_subspace(self) -> npt.ArrayLike: + """ + Args: + joint (Joint): Joint + + Returns: + npt.ArrayLike: motion subspace of the joint + """ + if self.type == "fixed": + return self.math.vertcat(0, 0, 0, 0, 0, 0) + elif self.type in ["revolute", "continuous"]: + return self.math.vertcat( + 0, + 0, + 0, + self.axis[0], + self.axis[1], + self.axis[2], + ) + elif self.type in ["prismatic"]: + return self.math.vertcat( + self.axis[0], + self.axis[1], + self.axis[2], + 0, + 0, + 0, + ) diff --git a/src/adam/model/std_factories/std_link.py b/src/adam/model/std_factories/std_link.py new file mode 100644 index 00000000..822ba68e --- /dev/null +++ b/src/adam/model/std_factories/std_link.py @@ -0,0 +1,41 @@ +import numpy.typing as npt +import urdf_parser_py.urdf + +from adam.core.spatial_math import SpatialMath +from adam.model import Link + + +class StdLink(Link): + """Standard Link class""" + + def __init__(self, link: urdf_parser_py.urdf.Link, math: SpatialMath): + self.math = math + self.name = link.name + self.visuals = link.visuals + self.inertial = link.inertial + self.collisions = link.collisions + self.origin = link.origin + + def spatial_inertia(self) -> npt.ArrayLike: + """ + Args: + link (Link): Link + + Returns: + npt.ArrayLike: the 6x6 inertia matrix expressed at the origin of the link (with rotation) + """ + I = self.inertial.inertia + mass = self.inertial.mass + o = self.inertial.origin.xyz + rpy = self.inertial.origin.rpy + return self.math.spatial_inertia(I, mass, o, rpy) + + def homogeneous(self) -> npt.ArrayLike: + """ + Returns: + npt.ArrayLike: the homogeneus transform of the link + """ + return self.math.H_from_Pos_RPY( + self.inertial.origin.xyz, + self.inertial.origin.rpy, + ) diff --git a/src/adam/model/std_factories/std_model.py b/src/adam/model/std_factories/std_model.py new file mode 100644 index 00000000..e7da13da --- /dev/null +++ b/src/adam/model/std_factories/std_model.py @@ -0,0 +1,68 @@ +import pathlib +from typing import List + +import urdf_parser_py.urdf + +from adam.core.spatial_math import SpatialMath +from adam.model import ModelFactory, StdJoint, StdLink + + +class URDFModelFactory(ModelFactory): + """This factory generates robot elements from urdf_parser_py + + Args: + ModelFactory: the Model factory + """ + + def __init__(self, path: str, math: SpatialMath): + self.math = math + if type(path) is not pathlib.Path: + path = pathlib.Path(path) + if not path.exists(): + raise FileExistsError(path) + + self.urdf_desc = urdf_parser_py.urdf.URDF.from_xml_file(path) + self.name = self.urdf_desc.name + + def get_joints(self) -> List[StdJoint]: + """ + Returns: + 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]: + """ + Returns: + List[StdLink]: build the list of the links + """ + return [ + self.build_link(l) for l in self.urdf_desc.links if l.inertial is not None + ] + + def get_frames(self) -> List[StdLink]: + """ + Returns: + List[StdLink]: build the list of the links + """ + return [self.build_link(l) for l in self.urdf_desc.links if l.inertial is None] + + def build_joint(self, joint: urdf_parser_py.urdf.Joint) -> StdJoint: + """ + Args: + joint (Joint): the urdf_parser_py joint + + Returns: + StdJoint: our joint representation + """ + return StdJoint(joint, self.math) + + def build_link(self, link: urdf_parser_py.urdf.Link) -> StdLink: + """ + Args: + link (Link): the urdf_parser_py link + + Returns: + StdLink: our link representation + """ + return StdLink(link, self.math) diff --git a/src/adam/model/tree.py b/src/adam/model/tree.py new file mode 100644 index 00000000..dc96bfe5 --- /dev/null +++ b/src/adam/model/tree.py @@ -0,0 +1,175 @@ +import dataclasses +from typing import Dict, Iterable, List, Tuple, Union + +from adam.model.abc_factories import Joint, Link + + +@dataclasses.dataclass +class Node: + """The node class""" + + name: str + link: Link + arcs: List[Joint] + children: List[Link] + parent: Link = None + parent_arc: Joint = None + + def __hash__(self) -> int: + return hash(self.name) + + 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 + """ + return self.link, self.parent_arc, self.parent + + +@dataclasses.dataclass +class Tree(Iterable): + """The directed tree class""" + + 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": + """builds the tree from the connectivity of the elements + + Args: + links (List[Link]) + joints (List[Joint]) + + Returns: + Tree: the directed tree + """ + nodes: Dict(str, Node) = { + l.name: Node( + name=l.name, link=l, arcs=[], children=[], parent=None, parent_arc=None + ) + for l in links + } + + for joint in joints: + # don't add the frames + if joint.parent not in nodes.keys() or joint.child not in nodes.keys(): + continue + + if joint.parent not in {l.name for l in nodes[joint.parent].children}: + nodes[joint.parent].children.append(nodes[joint.child]) + nodes[joint.parent].arcs.append(joint) + nodes[joint.child].parent = nodes[joint.parent].link + nodes[joint.child].parent_arc = joint + + root_link = [l for l in nodes if nodes[l].parent is None] + if len(root_link) != 1: + raise ValueError("The model has more than one root link") + return Tree(nodes, root_link[0]) + + def print(self, root) -> str: + """prints the tree + + Args: + root (str): the root of the tree + """ + import pptree + + pptree.print_tree(self.graph[root]) + + 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 + """ + ordered_list = [start] + self.get_children(self.graph[start], ordered_list) + return ordered_list + + @classmethod + 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 + """ + if node.children is not []: + for child in node.children: + list.append(child.name) + cls.get_children(child, list) + + def get_idx_from_name(self, name: str) -> int: + """ + Args: + name (str): node name + + Returns: + int: the index of the node in the ordered list + """ + return self.ordered_nodes_list.index(name) + + def get_name_from_idx(self, idx: int) -> str: + """ + Args: + idx (int): the index in the ordered list + + Returns: + str: the corresponding node name + """ + return self.ordered_nodes_list[idx] + + def get_node_from_name(self, name: str) -> Node: + """ + Args: + name (str): the node name + + Returns: + Node: the node istance + """ + return self.graph[name] + + def __iter__(self) -> Node: + """This method allows to iterate on the model + Returns: + Node: the node istance + + Yields: + Iterator[Node]: the list of the nodes + """ + yield from [self.graph[name] for name in self.ordered_nodes_list] + + def __reversed__(self) -> Node: + """ + Returns: + Node + + Yields: + Iterator[Node]: the reversed nodes list + """ + yield from reversed(self) + + def __getitem__(self, key) -> Node: + """get the item at key in the model + + Args: + key (Union[int, Slice]): _description_ + + Returns: + Node: _description_ + """ + return self.graph[self.ordered_nodes_list[key]] + + def __len__(self) -> int: + """ + Returns: + int: the length of the model + """ + return len(self.ordered_nodes_list) diff --git a/src/adam/numpy/__init__.py b/src/adam/numpy/__init__.py index c42c5cb8..b94c17b8 100644 --- a/src/adam/numpy/__init__.py +++ b/src/adam/numpy/__init__.py @@ -3,3 +3,4 @@ # GNU Lesser General Public License v2.1 or any later version. from .computations import KinDynComputations +from .numpy_like import NumpyLike diff --git a/src/adam/numpy/computations.py b/src/adam/numpy/computations.py index e8bfa43b..e0fe77d6 100644 --- a/src/adam/numpy/computations.py +++ b/src/adam/numpy/computations.py @@ -5,10 +5,11 @@ import numpy as np from adam.core.rbd_algorithms import RBDAlgorithms -from adam.numpy.numpy_like import NumpyLike +from adam.model import Model, URDFModelFactory +from adam.numpy.numpy_like import SpatialMath -class KinDynComputations(RBDAlgorithms, NumpyLike): +class KinDynComputations: """This is a small class that retrieves robot quantities using NumPy in mixed representation, for Floating Base systems - as humanoid robots. """ @@ -26,12 +27,12 @@ def __init__( joints_name_list (list): list of the actuated joints root_link (str, optional): the first link. Defaults to 'root_link'. """ - super().__init__( - urdfstring=urdfstring, - joints_name_list=joints_name_list, - root_link=root_link, - gravity=gravity, - ) + math = SpatialMath() + factory = URDFModelFactory(path=urdfstring, math=math) + model = Model.build(factory=factory, joints_name_list=joints_name_list) + self.rbdalgos = RBDAlgorithms(model=model, math=math) + self.NDoF = model.NDoF + self.g = gravity def mass_matrix( self, base_transform: np.ndarray, joint_positions: np.ndarray @@ -45,7 +46,7 @@ def mass_matrix( Returns: M (np.ndarray): Mass Matrix """ - [M, _] = super().crba(base_transform, joint_positions) + [M, _] = self.rbdalgos.crba(base_transform, joint_positions) return M.array def centroidal_momentum_matrix( @@ -60,7 +61,7 @@ def centroidal_momentum_matrix( Returns: Jcc (np.ndarray): Centroidal Momentum matrix """ - [_, Jcm] = super().crba(base_transform, s) + [_, Jcm] = self.rbdalgos.crba(base_transform, s) return Jcm.array def forward_kinematics( @@ -76,11 +77,9 @@ def forward_kinematics( Returns: T_fk (np.ndarray): The fk represented as Homogenous transformation matrix """ - return ( - super() - .forward_kinematics(frame, base_transform, joint_positions) - .array.squeeze() - ) + return self.rbdalgos.forward_kinematics( + frame, base_transform, joint_positions + ).array.squeeze() def jacobian( self, frame: str, base_transform: np.ndarray, joint_positions: np.ndarray @@ -95,7 +94,9 @@ def jacobian( Returns: J_tot (np.ndarray): The Jacobian relative to the frame """ - return super().jacobian(frame, base_transform, joint_positions).array.squeeze() + return self.rbdalgos.jacobian( + frame, base_transform, joint_positions + ).array.squeeze() def relative_jacobian(self, frame: str, joint_positions: np.ndarray) -> np.ndarray: """Returns the Jacobian between the root link and a specified frame frames @@ -107,7 +108,7 @@ def relative_jacobian(self, frame: str, joint_positions: np.ndarray) -> np.ndarr Returns: J (np.ndarray): The Jacobian between the root and the frame """ - return super().relative_jacobian(frame, joint_positions).array + return self.rbdalgos.relative_jacobian(frame, joint_positions).array def CoM_position( self, base_transform: np.ndarray, joint_positions: np.ndarray @@ -121,7 +122,9 @@ def CoM_position( Returns: CoM (np.ndarray): The CoM position """ - return super().CoM_position(base_transform, joint_positions).array.squeeze() + return self.rbdalgos.CoM_position( + base_transform, joint_positions + ).array.squeeze() def bias_force( self, @@ -142,17 +145,13 @@ def bias_force( Returns: h (np.ndarray): the bias force """ - return ( - super() - .rnea( - base_transform, - joint_positions, - base_velocity.reshape(6, 1), - joint_velocities, - self.g, - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + base_velocity.reshape(6, 1), + joint_velocities, + self.g, + ).array.squeeze() def coriolis_term( self, @@ -174,17 +173,13 @@ def coriolis_term( C (np.ndarray): the Coriolis term """ # set in the bias force computation the gravity term to zero - return ( - super() - .rnea( - base_transform, - joint_positions, - base_velocity.reshape(6, 1), - joint_velocities, - np.zeros(6), - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + base_velocity.reshape(6, 1), + joint_velocities, + np.zeros(6), + ).array.squeeze() def gravity_term( self, base_transform: np.ndarray, joint_positions: np.ndarray @@ -199,14 +194,18 @@ def gravity_term( Returns: G (np.ndarray): the gravity term """ - return ( - super() - .rnea( - base_transform, - joint_positions, - np.zeros(6).reshape(6, 1), - np.zeros(self.NDoF), - self.g, - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + np.zeros(6).reshape(6, 1), + np.zeros(self.NDoF), + self.g, + ).array.squeeze() + + def get_total_mass(self) -> float: + """Returns the total mass of the robot + + Returns: + mass: The total mass + """ + return self.rbdalgos.get_total_mass() diff --git a/src/adam/numpy/numpy_like.py b/src/adam/numpy/numpy_like.py index 4cfdcd46..ed577159 100644 --- a/src/adam/numpy/numpy_like.py +++ b/src/adam/numpy/numpy_like.py @@ -8,7 +8,7 @@ import numpy as np import numpy.typing as npt -from adam.core.spatial_math import ArrayLike +from adam.core.spatial_math import ArrayLike, ArrayLikeFactory, SpatialMath @dataclass @@ -20,11 +20,7 @@ class NumpyLike(ArrayLike): def __setitem__(self, idx, value: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": """Overrides set item operator""" if type(self) is type(value): - value.array = np.squeeze(value.array) - try: - self.array[idx] = value.array - except: - self.array[idx] = value.array.reshape(-1, 1) + self.array[idx] = value.array.reshape(self.array[idx].shape) else: self.array[idx] = value @@ -103,13 +99,15 @@ def __sub__(self, other: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": def __rsub__(self, other: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": """Overrides - operator""" if type(self) is not type(other): - return NumpyLike(self.array.squeeze() - other.squeeze()) - return NumpyLike(self.array.squeeze() - other.array.squeeze()) + return NumpyLike(other.squeeze() - self.array.squeeze()) + return NumpyLike(other.array.squeeze() - self.array.squeeze()) def __neg__(self): """Overrides - operator""" return NumpyLike(-self.array) + +class NumpyLikeFactory(ArrayLikeFactory): @staticmethod def zeros(*x) -> "NumpyLike": """ @@ -118,18 +116,6 @@ def zeros(*x) -> "NumpyLike": """ return NumpyLike(np.zeros(x)) - @staticmethod - def vertcat(*x: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": - """ - Returns: - NumpyLike: vertical concatenation of x - """ - if isinstance(x[0], NumpyLike): - v = np.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) - else: - v = np.vstack([x[i] for i in range(len(x))]).reshape(-1, 1) - return NumpyLike(v) - @staticmethod def eye(x: int) -> "NumpyLike": """ @@ -141,20 +127,6 @@ def eye(x: int) -> "NumpyLike": """ return NumpyLike(np.eye(x)) - @staticmethod - def skew(x: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": - """ - Args: - x (Union[NumpyLike, npt.ArrayLike]): vector - - Returns: - NumpyLike: the skew symmetric matrix from x - """ - if not isinstance(x, NumpyLike): - return -np.cross(np.array(x), np.eye(3), axisa=0, axisb=0) - x = x.array - return NumpyLike(-np.cross(np.array(x), np.eye(3), axisa=0, axisb=0)) - @staticmethod def array(*x) -> "NumpyLike": """ @@ -163,6 +135,11 @@ def array(*x) -> "NumpyLike": """ return NumpyLike(np.array(x)) + +class SpatialMath(SpatialMath): + def __init__(self): + super().__init__(NumpyLikeFactory()) + @staticmethod def sin(x: npt.ArrayLike) -> "NumpyLike": """ @@ -198,3 +175,29 @@ def outer(x: npt.ArrayLike, y: npt.ArrayLike) -> "NumpyLike": x = np.array(x) y = np.array(y) return NumpyLike(np.outer(x, y)) + + @staticmethod + def vertcat(*x: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": + """ + Returns: + NumpyLike: vertical concatenation of x + """ + if isinstance(x[0], NumpyLike): + v = np.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) + else: + v = np.vstack([x[i] for i in range(len(x))]).reshape(-1, 1) + return NumpyLike(v) + + @staticmethod + def skew(x: Union["NumpyLike", npt.ArrayLike]) -> "NumpyLike": + """ + Args: + x (Union[NumpyLike, npt.ArrayLike]): vector + + Returns: + NumpyLike: the skew symmetric matrix from x + """ + if not isinstance(x, NumpyLike): + return -np.cross(np.array(x), np.eye(3), axisa=0, axisb=0) + x = x.array + return NumpyLike(-np.cross(np.array(x), np.eye(3), axisa=0, axisb=0)) diff --git a/src/adam/parametric/computations.py b/src/adam/parametric/computations.py new file mode 100644 index 00000000..50b7ebe3 --- /dev/null +++ b/src/adam/parametric/computations.py @@ -0,0 +1,174 @@ +# 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. + +import casadi as cs +import numpy as np + +from adam.casadi.casadi_like import SpatialMath +from adam.core import RBDAlgorithms +from adam.model import Model +from adam.parametric import ParametricModelFactory + + +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. + """ + + def __init__( + self, + urdfstring: str, + joints_name_list: list, + root_link: str = "root_link", + 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")), + ) -> None: + """ + Args: + urdfstring (str): path of the urdf + joints_name_list (list): list of the actuated joints + root_link (str, optional): the first link. Defaults to 'root_link'. + """ + factory = URDFModelFactory(urdfstring, SpatialMath()) + model = Model.build(factory=factory, joints_name_list=joints_name_list) + self.rbdalgos = RBDAlgorithms(model=model) + self.NDoF = self.rbdalgos.NDoF + self.g = gravity + self.f_opts = f_opts + + def mass_matrix_fun(self) -> cs.Function: + """Returns the Mass Matrix functions computed the CRBA + + Returns: + M (casADi function): Mass Matrix + """ + T_b = cs.SX.sym("T_b", 4, 4) + s = cs.SX.sym("s", self.NDoF) + [M, _] = self.rbdalgos.crba(T_b, s) + return cs.Function("M", [T_b, s], [M.array], self.f_opts) + + def centroidal_momentum_matrix_fun(self) -> cs.Function: + """Returns the Centroidal Momentum Matrix functions computed the CRBA + + Returns: + Jcc (casADi function): Centroidal Momentum matrix + """ + T_b = cs.SX.sym("T_b", 4, 4) + s = cs.SX.sym("s", self.NDoF) + [_, Jcm] = self.rbdalgos.crba(T_b, s) + return cs.Function("Jcm", [T_b, s], [Jcm.array], self.f_opts) + + def forward_kinematics_fun(self, frame: str) -> cs.Function: + """Computes the forward kinematics relative to the specified frame + + Args: + frame (str): The frame to which the fk will be computed + + Returns: + T_fk (casADi function): The fk represented as Homogenous transformation matrix + """ + s = cs.SX.sym("s", self.NDoF) + T_b = cs.SX.sym("T_b", 4, 4) + T_fk = self.rbdalgos.forward_kinematics(frame, T_b, s) + return cs.Function("T_fk", [T_b, s], [T_fk.array], self.f_opts) + + def jacobian_fun(self, frame: str) -> cs.Function: + """Returns the Jacobian relative to the specified frame + + Args: + frame (str): The frame to which the jacobian will be computed + + Returns: + J_tot (casADi function): The Jacobian relative to the frame + """ + s = cs.SX.sym("s", self.NDoF) + T_b = cs.SX.sym("T_b", 4, 4) + J_tot = self.rbdalgos.jacobian(frame, T_b, s) + return cs.Function("J_tot", [T_b, s], [J_tot.array], self.f_opts) + + def relative_jacobian_fun(self, frame: str) -> cs.Function: + """Returns the Jacobian between the root link and a specified frame frames + + Args: + frame (str): The tip of the chain + + Returns: + J (casADi function): The Jacobian between the root and the frame + """ + s = cs.SX.sym("s", self.NDoF) + J = self.rbdalgos.relative_jacobian(frame, s) + return cs.Function("J", [s], [J.array], self.f_opts) + + def CoM_position_fun(self) -> cs.Function: + """Returns the CoM positon + + Returns: + com (casADi function): The CoM position + """ + s = cs.SX.sym("s", self.NDoF) + T_b = cs.SX.sym("T_b", 4, 4) + com_pos = self.rbdalgos.CoM_position(T_b, s) + return cs.Function("CoM_pos", [T_b, s], [com_pos.array], self.f_opts) + + def bias_force_fun(self) -> cs.Function: + """Returns the bias force of the floating-base dynamics equation, + using a reduced RNEA (no acceleration and external forces) + + Returns: + h (casADi function): the bias force + """ + T_b = cs.SX.sym("T_b", 4, 4) + s = cs.SX.sym("s", self.NDoF) + v_b = cs.SX.sym("v_b", 6) + s_dot = cs.SX.sym("s_dot", self.NDoF) + h = self.rbdalgos.rnea(T_b, s, v_b, s_dot, self.g) + return cs.Function("h", [T_b, s, v_b, s_dot], [h.array], self.f_opts) + + def coriolis_term_fun(self) -> cs.Function: + """Returns the coriolis term of the floating-base dynamics equation, + using a reduced RNEA (no acceleration and external forces) + + Returns: + C (casADi function): the Coriolis term + """ + T_b = cs.SX.sym("T_b", 4, 4) + q = cs.SX.sym("q", self.NDoF) + v_b = cs.SX.sym("v_b", 6) + q_dot = cs.SX.sym("q_dot", self.NDoF) + # set in the bias force computation the gravity term to zero + C = self.rbdalgos.rnea(T_b, q, v_b, q_dot, np.zeros(6)) + return cs.Function("C", [T_b, q, v_b, q_dot], [C.array], self.f_opts) + + def gravity_term_fun(self) -> cs.Function: + """Returns the gravity term of the floating-base dynamics equation, + using a reduced RNEA (no acceleration and external forces) + + Returns: + G (casADi function): the gravity term + """ + T_b = cs.SX.sym("T_b", 4, 4) + q = cs.SX.sym("q", self.NDoF) + # set in the bias force computation the velocity to zero + G = self.rbdalgos.rnea(T_b, q, np.zeros(6), np.zeros(self.NDoF), self.g) + return cs.Function("G", [T_b, q], [G.array], self.f_opts) + + def forward_kinematics(self, frame, T_b, s) -> cs.Function: + """Computes the forward kinematics relative to the specified frame + + Args: + frame (str): The frame to which the fk will be computed + + Returns: + T_fk (casADi function): The fk represented as Homogenous transformation matrix + """ + + return self.rbdalgos.forward_kinematics(frame, T_b, s) + + def get_total_mass(self): + """Returns the total mass of the robot + + Returns: + mass: The total mass + """ + return self.rbdalgos.get_total_mass() diff --git a/src/adam/pytorch/__init__.py b/src/adam/pytorch/__init__.py index c42c5cb8..8a3a50b6 100644 --- a/src/adam/pytorch/__init__.py +++ b/src/adam/pytorch/__init__.py @@ -3,3 +3,4 @@ # GNU Lesser General Public License v2.1 or any later version. from .computations import KinDynComputations +from .torch_like import TorchLike diff --git a/src/adam/pytorch/computations.py b/src/adam/pytorch/computations.py index 1e4f29b3..d2f257a9 100644 --- a/src/adam/pytorch/computations.py +++ b/src/adam/pytorch/computations.py @@ -6,10 +6,11 @@ import torch from adam.core.rbd_algorithms import RBDAlgorithms -from adam.pytorch.torch_like import TorchLike +from adam.model import Model, URDFModelFactory +from adam.pytorch.torch_like import SpatialMath -class KinDynComputations(RBDAlgorithms, TorchLike): +class KinDynComputations: """This is a small class that retrieves robot quantities using Pytorch in mixed representation, for Floating Base systems - as humanoid robots. """ @@ -27,12 +28,12 @@ def __init__( joints_name_list (list): list of the actuated joints root_link (str, optional): the first link. Defaults to 'root_link'. """ - super().__init__( - urdfstring=urdfstring, - joints_name_list=joints_name_list, - root_link=root_link, - gravity=gravity, - ) + math = SpatialMath() + factory = URDFModelFactory(path=urdfstring, math=math) + model = Model.build(factory=factory, joints_name_list=joints_name_list) + self.rbdalgos = RBDAlgorithms(model=model, math=math) + self.NDoF = self.rbdalgos.NDoF + self.g = gravity def mass_matrix( self, base_transform: torch.Tensor, s: torch.Tensor @@ -46,7 +47,7 @@ def mass_matrix( Returns: M (torch.tensor): Mass Matrix """ - [M, _] = super().crba(base_transform, s) + [M, _] = self.rbdalgos.crba(base_transform, s) return M.array def centroidal_momentum_matrix( @@ -61,7 +62,7 @@ def centroidal_momentum_matrix( Returns: Jcc (torch.tensor): Centroidal Momentum matrix """ - [_, Jcm] = super().crba(base_transform, s) + [_, Jcm] = self.rbdalgos.crba(base_transform, s) return Jcm.array def forward_kinematics( @@ -78,7 +79,7 @@ def forward_kinematics( T_fk (torch.tensor): The fk represented as Homogenous transformation matrix """ return ( - super().forward_kinematics( + self.rbdalgos.forward_kinematics( frame, torch.FloatTensor(base_transform), torch.FloatTensor(s) ) ).array @@ -96,7 +97,7 @@ def jacobian( Returns: J_tot (torch.tensor): The Jacobian relative to the frame """ - return super().jacobian(frame, base_transform, joint_positions).array + return self.rbdalgos.jacobian(frame, base_transform, joint_positions).array def relative_jacobian(self, frame, joint_positions: torch.Tensor) -> torch.Tensor: """Returns the Jacobian between the root link and a specified frame frames @@ -108,7 +109,7 @@ def relative_jacobian(self, frame, joint_positions: torch.Tensor) -> torch.Tenso Returns: J (torch.tensor): The Jacobian between the root and the frame """ - return super().relative_jacobian(frame, joint_positions).array + return self.rbdalgos.relative_jacobian(frame, joint_positions).array def CoM_position( self, base_transform: torch.Tensor, joint_positions: torch.Tensor @@ -122,7 +123,9 @@ def CoM_position( Returns: com (torch.tensor): The CoM position """ - return super().CoM_position(base_transform, joint_positions).array.squeeze() + return self.rbdalgos.CoM_position( + base_transform, joint_positions + ).array.squeeze() def bias_force( self, @@ -143,17 +146,13 @@ def bias_force( Returns: h (torch.tensor): the bias force """ - return ( - super() - .rnea( - base_transform, - s, - base_velocity.reshape(6, 1), - joint_velocities, - self.g, - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + s, + base_velocity.reshape(6, 1), + joint_velocities, + self.g, + ).array.squeeze() def coriolis_term( self, @@ -175,17 +174,13 @@ def coriolis_term( C (torch.tensor): the Coriolis term """ # set in the bias force computation the gravity term to zero - return ( - super() - .rnea( - base_transform, - joint_positions, - base_velocity.reshape(6, 1), - joint_velocities, - torch.zeros(6), - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + joint_positions, + base_velocity.reshape(6, 1), + joint_velocities, + torch.zeros(6), + ).array.squeeze() def gravity_term( self, base_transform: torch.Tensor, base_positions: torch.Tensor @@ -200,14 +195,18 @@ def gravity_term( Returns: G (torch.tensor): the gravity term """ - return ( - super() - .rnea( - base_transform, - base_positions, - torch.zeros(6).reshape(6, 1), - torch.zeros(self.NDoF), - torch.FloatTensor(self.g), - ) - .array.squeeze() - ) + return self.rbdalgos.rnea( + base_transform, + base_positions, + torch.zeros(6).reshape(6, 1), + torch.zeros(self.NDoF), + torch.FloatTensor(self.g), + ).array.squeeze() + + def get_total_mass(self) -> float: + """Returns the total mass of the robot + + Returns: + mass: The total mass + """ + return self.rbdalgos.get_total_mass() diff --git a/src/adam/pytorch/torch_like.py b/src/adam/pytorch/torch_like.py index f9e8fe97..50eaf541 100644 --- a/src/adam/pytorch/torch_like.py +++ b/src/adam/pytorch/torch_like.py @@ -8,7 +8,8 @@ import numpy.typing as ntp import torch -from adam.core.spatial_math import ArrayLike +from adam.core.spatial_math import ArrayLike, ArrayLikeFactory, SpatialMath +from adam.numpy import NumpyLike @dataclass @@ -20,11 +21,7 @@ class TorchLike(ArrayLike): def __setitem__(self, idx, value: Union["TorchLike", ntp.ArrayLike]) -> "TorchLike": """Overrides set item operator""" if type(self) is type(value): - value.array = torch.squeeze(value.array) - try: - self.array[idx] = value.array - except: - self.array[idx] = value.array.reshape(-1, 1) + self.array[idx] = value.array.reshape(self.array[idx].shape) else: self.array[idx] = torch.FloatTensor(value) @@ -115,6 +112,8 @@ def __neg__(self) -> "TorchLike": """Overrides - operator""" return TorchLike(-self.array) + +class TorchLikeFactory(ArrayLikeFactory): @staticmethod def zeros(*x: int) -> "TorchLike": """ @@ -123,18 +122,6 @@ def zeros(*x: int) -> "TorchLike": """ return TorchLike(torch.zeros(x).float()) - @staticmethod - def vertcat(*x: ntp.ArrayLike) -> "TorchLike": - """ - Returns: - TorchLike: vertical concatenation of x - """ - if isinstance(x[0], TorchLike): - v = torch.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) - else: - v = torch.FloatTensor(x).reshape(-1, 1) - return TorchLike(v) - @staticmethod def eye(x: int) -> "TorchLike": """ @@ -146,26 +133,6 @@ def eye(x: int) -> "TorchLike": """ return TorchLike(torch.eye(x).float()) - @staticmethod - def skew(x: Union["TorchLike", ntp.ArrayLike]) -> "TorchLike": - """ - Args: - x (Union[TorchLike, ntp.ArrayLike]): vector - - Returns: - TorchLike: skew matrix from x - """ - if not isinstance(x, TorchLike): - return TorchLike( - torch.FloatTensor( - [[0, -x[2], x[1]], [x[2], 0, -x[0]], [-x[1], x[0], 0]] - ) - ) - x = x.array - return TorchLike( - torch.FloatTensor([[0, -x[2], x[1]], [x[2], 0, -x[0]], [-x[1], x[0], 0]]) - ) - @staticmethod def array(*x: ntp.ArrayLike) -> "TorchLike": """ @@ -174,6 +141,11 @@ def array(*x: ntp.ArrayLike) -> "TorchLike": """ return TorchLike(torch.FloatTensor(x)) + +class SpatialMath(SpatialMath): + def __init__(self): + super().__init__(TorchLikeFactory()) + @staticmethod def sin(x: ntp.ArrayLike) -> "TorchLike": """ @@ -209,3 +181,35 @@ def outer(x: ntp.ArrayLike, y: ntp.ArrayLike) -> "TorchLike": TorchLike: outer product of x and y """ return TorchLike(torch.outer(torch.tensor(x), torch.tensor(y))) + + @staticmethod + def skew(x: Union["TorchLike", ntp.ArrayLike]) -> "TorchLike": + """ + Args: + x (Union[TorchLike, ntp.ArrayLike]): vector + + Returns: + TorchLike: skew matrix from x + """ + if not isinstance(x, TorchLike): + return TorchLike( + torch.FloatTensor( + [[0, -x[2], x[1]], [x[2], 0, -x[0]], [-x[1], x[0], 0]] + ) + ) + x = x.array + return TorchLike( + torch.FloatTensor([[0, -x[2], x[1]], [x[2], 0, -x[0]], [-x[1], x[0], 0]]) + ) + + @staticmethod + def vertcat(*x: ntp.ArrayLike) -> "TorchLike": + """ + Returns: + TorchLike: vertical concatenation of x + """ + if isinstance(x[0], TorchLike): + v = torch.vstack([x[i].array for i in range(len(x))]).reshape(-1, 1) + else: + v = torch.FloatTensor(x).reshape(-1, 1) + return TorchLike(v) diff --git a/tests/test_CasADi_computations.py b/tests/test_CasADi_computations.py index 166ab996..f5dce275 100644 --- a/tests/test_CasADi_computations.py +++ b/tests/test_CasADi_computations.py @@ -15,7 +15,7 @@ np.random.seed(42) -model_path = gym_ignition_models.get_model_file("iCubGazeboV2_5") +model_path = str(gym_ignition_models.get_model_file("iCubGazeboV2_5")) joints_name_list = [ "torso_pitch", diff --git a/tests/test_Jax_computations.py b/tests/test_Jax_computations.py index 53efa5ec..8b1c7d69 100644 --- a/tests/test_Jax_computations.py +++ b/tests/test_Jax_computations.py @@ -17,7 +17,7 @@ np.random.seed(42) config.update("jax_enable_x64", True) -model_path = gym_ignition_models.get_model_file("iCubGazeboV2_5") +model_path = str(gym_ignition_models.get_model_file("iCubGazeboV2_5")) joints_name_list = [ "torso_pitch", @@ -99,12 +99,12 @@ def H_from_Pos_RPY_idyn(xyz, rpy): s_dot_ = joints_dot_val -def test_mass_matrix(): - mass_mx = idyntree.MatrixDynSize() - kinDyn.getFreeFloatingMassMatrix(mass_mx) - mass_mxNumpy = mass_mx.toNumPy() - mass_test = comp.mass_matrix(H_b, s_) - assert np.asarray(mass_test) - mass_mxNumpy == pytest.approx(0.0, abs=1e-5) +# def test_mass_matrix(): +mass_mx = idyntree.MatrixDynSize() +kinDyn.getFreeFloatingMassMatrix(mass_mx) +mass_mxNumpy = mass_mx.toNumPy() +mass_test = comp.mass_matrix(H_b, s_) +assert np.asarray(mass_test) - mass_mxNumpy == pytest.approx(0.0, abs=1e-5) def test_CMM(): diff --git a/tests/test_NumPy_computations.py b/tests/test_NumPy_computations.py index cbccdc0e..4249288e 100644 --- a/tests/test_NumPy_computations.py +++ b/tests/test_NumPy_computations.py @@ -14,7 +14,7 @@ np.random.seed(42) -model_path = gym_ignition_models.get_model_file("iCubGazeboV2_5") +model_path = str(gym_ignition_models.get_model_file("iCubGazeboV2_5")) joints_name_list = [ "torso_pitch", diff --git a/tests/test_pytorch_computations.py b/tests/test_pytorch_computations.py index b4c8beaf..aa3b35d5 100644 --- a/tests/test_pytorch_computations.py +++ b/tests/test_pytorch_computations.py @@ -16,7 +16,7 @@ np.random.seed(42) torch.set_default_dtype(torch.float64) -model_path = gym_ignition_models.get_model_file("iCubGazeboV2_5") +model_path = str(gym_ignition_models.get_model_file("iCubGazeboV2_5")) joints_name_list = [ "torso_pitch",