adam.core.rbd_algorithms#

Classes#

RBDAlgorithms

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.

model[source]#
NDoF[source]#
math[source]#
frame_velocity_representation[source]#
_root_spatial_transform[source]#
_root_motion_subspace[source]#
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)[source]#

Batched Composite Rigid Body Algorithm (CRBA) + Orin’s Centroidal Momentum Matrix.

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The mass matrix and the centroidal momentum matrix

Return type:

M, Jcm (npt.ArrayLike, 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]#

Returns the Jacobian for 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 Jacobian for the specified frame

Return type:

npt.ArrayLike

relative_jacobian(frame: str, joint_positions: numpy.typing.ArrayLike) numpy.typing.ArrayLike[source]#

Returns the Jacobian between the root link and a specified frame.

Parameters:
  • frame (str) – The tip of the chain

  • joint_positions (npt.ArrayLike) – The joints position

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 time derivative for 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 spatial velocity of the base

  • joint_velocities (npt.ArrayLike) – The joints velocities

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 (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The CoM position

Return type:

com (npt.ArrayLike)

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 (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

Returns:

The CoM Jacobian

Return type:

J_com (npt.ArrayLike)

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

Batched Recursive Newton-Euler (reduced: no joint/base accelerations, no external forces).

Parameters:
  • 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 spatial velocity

  • joint_velocities (npt.ArrayLike) – The joints velocities

  • g (npt.ArrayLike) – The gravity vector

Returns:

The vector of generalized forces

Return type:

tau (npt.ArrayLike)

aba(base_transform: numpy.typing.ArrayLike, joint_positions: numpy.typing.ArrayLike, base_velocity: numpy.typing.ArrayLike, joint_velocities: numpy.typing.ArrayLike, joint_torques: numpy.typing.ArrayLike, g: numpy.typing.ArrayLike, external_wrenches: dict[str, numpy.typing.ArrayLike] | None = None) numpy.typing.ArrayLike[source]#

Featherstone Articulated Body Algorithm for floating-base forward dynamics.

Parameters:
  • base_transform (npt.ArrayLike) – The homogenous transform from base to world frame

  • joint_positions (npt.ArrayLike) – The joints position

  • base_velocity (npt.ArrayLike) – The spatial velocity of the base

  • joint_velocities (npt.ArrayLike) – The joints velocities

  • joint_torques (npt.ArrayLike) – The joints torques/forces

  • g (npt.ArrayLike | None, optional) – The gravity vector

  • external_wrenches (dict[str, npt.ArrayLike] | None, optional) – A dictionary of external wrenches applied to specific links. Keys are link names, and values are 6D wrench vectors. Defaults to None.

Returns:

The spatial acceleration of the base and joints accelerations

Return type:

accelerations (npt.ArrayLike)

_convert_to_arraylike(*args)[source]#

Convert inputs to ArrayLike if they are not already. :param *args: Input arguments to be converted.

Returns:

Converted arguments as ArrayLike.

_prepare_tree_cache() None[source]#

Pre-compute static tree data so the dynamic algorithms avoid repeated Python work.