adam.core.rbd_algorithms#
Classes#
This is a small class that implements Rigid body algorithms retrieving robot quantities, for Floating Base systems - as humanoid robots. |
Module Contents#
- class adam.core.rbd_algorithms.RBDAlgorithms(model: adam.model.Model, math: adam.core.spatial_math.SpatialMath)[source]#
This is a small class that implements Rigid body algorithms retrieving robot quantities, for Floating Base systems - as humanoid robots.
- set_frame_velocity_representation(representation: adam.core.constants.Representations)[source]#
Sets the frame velocity representation
- Parameters:
representation (str) – The representation of the frame velocity
- crba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
- This function computes the Composite Rigid body algorithm (Roy Featherstone) that computes the Mass Matrix.
The algorithm is complemented with Orin’s modifications computing the Centroidal Momentum Matrix
- Parameters:
base_transform (npt.ArrayLike) – The homogenous transform from base to world frame
joint_positions (npt.ArrayLike) – The joints position
- Returns:
Mass Matrix Jcm (npt.ArrayLike): Centroidal Momentum Matrix
- Return type:
M (npt.ArrayLike)
- forward_kinematics(frame, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Computes the forward kinematics relative to the specified frame
- Parameters:
frame (str) – The frame to which the fk will be computed
base_transform (npt.ArrayLike) – The homogenous transform from base to world frame
joint_positions (npt.ArrayLike) – The joints position
- Returns:
The fk represented as Homogenous transformation matrix
- Return type:
I_H_L (npt.ArrayLike)
- joints_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Returns the Jacobian relative to the specified frame
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (npt.ArrayLike) – The homogenous transform from base to world frame
joint_positions (npt.ArrayLike) – The joints position
- Returns:
The Joints Jacobian relative to the frame
- Return type:
J (npt.ArrayLike)
- jacobian(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
- relative_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Returns the Jacobian between the root link and a specified frame :param frame: The tip of the chain :type frame: str :param joint_positions: The joints position :type joint_positions: npt.ArrayLike
- Returns:
The 6 x NDoF Jacobian between the root and the frame
- Return type:
J (npt.ArrayLike)
- jacobian_dot(frame: str, base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Returns the Jacobian derivative relative to the specified frame
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (npt.ArrayLike) – The homogenous transform from base to world frame
joint_positions (npt.ArrayLike) – The joints position
base_velocity (npt.ArrayLike) – The base velocity
joint_velocities (npt.ArrayLike) – The joints velocity
- Returns:
The Jacobian derivative relative to the frame
- Return type:
J_dot (npt.ArrayLike)
- CoM_position(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Returns the CoM position
- Parameters:
base_transform (T) – The homogenous transform from base to world frame
joint_positions (T) – The joints position
- Returns:
The CoM position
- Return type:
com (T)
- CoM_jacobian(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Returns the center of mass (CoM) Jacobian using the centroidal momentum matrix.
- Parameters:
base_transform (T) – The homogenous transform from base to world frame
joint_positions (T) – The joints position
- Returns:
The CoM Jacobian
- Return type:
J_com (T)
- get_total_mass()[source]#
Returns the total mass of the robot
- Returns:
The total mass
- Return type:
mass
- rnea(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike) numpy.typing.ArrayLike [source]#
Implementation of reduced Recursive Newton-Euler algorithm (no acceleration and external forces). For now used to compute the bias force term
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (T) – The homogenous transform from base to world frame
joint_positions (T) – The joints position
base_velocity (T) – The base velocity
joint_velocities (T) – The joints velocity
g (T) – The 6D gravity acceleration
- Returns:
generalized force variables
- Return type:
tau (T)