adam.numpy.computations#

Classes#

KinDynComputations

This is a small class that retrieves robot quantities using NumPy for Floating Base systems.

Module Contents#

class adam.numpy.computations.KinDynComputations(urdfstring: str, joints_name_list: list = None, root_link: str = None, gravity: numpy.array = np.array([0, 0, -9.80665, 0, 0, 0]))[source]#

This is a small class that retrieves robot quantities using NumPy for Floating Base systems.

rbdalgos[source]#
NDoF[source]#
g[source]#
set_frame_velocity_representation(representation: adam.core.constants.Representations) None[source]#

Sets the representation of the velocity of the frames

Parameters:

representation (Representations) – The representation of the velocity

mass_matrix(base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Returns the Mass Matrix functions computed the CRBA

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

  • joint_positions (np.ndarray) – The joints position

Returns:

Mass Matrix

Return type:

M (np.ndarray)

centroidal_momentum_matrix(base_transform: numpy.ndarray, s: numpy.ndarray) numpy.ndarray[source]#

Returns the Centroidal Momentum Matrix functions computed the CRBA

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

  • joint_positions (np.ndarray) – The joint positions

Returns:

Centroidal Momentum matrix

Return type:

Jcc (np.ndarray)

forward_kinematics(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Computes the forward kinematics relative to the specified frame

Parameters:
  • frame (str) – The frame to which the fk will be computed

  • base_transform (np.ndarray) – The homogenous transform from base to world frame

  • joint_positions (np.ndarray) – The joints position

Returns:

The fk represented as Homogenous transformation matrix

Return type:

H (np.ndarray)

jacobian(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Returns the Jacobian relative to the specified frame

Parameters:
  • frame (str) – The frame to which the jacobian will be computed

  • base_transform (np.ndarray) – The homogenous transform from base to world frame

  • joint_positions (np.ndarray) – The joints position

Returns:

The Jacobian relative to the frame

Return type:

J_tot (np.ndarray)

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

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

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

  • joint_positions (np.ndarray) – The joints position

Returns:

The Jacobian between the root and the frame

Return type:

J (np.ndarray)

jacobian_dot(frame: str, base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray) numpy.ndarray[source]#

Returns the Jacobian derivative relative to the specified frame

Parameters:
  • frame (str) – The frame to which the jacobian will be computed

  • base_transform (np.ndarray) – The homogenous transform from base to world frame

  • joint_positions (np.ndarray) – The joints position

  • base_velocity (np.ndarray) – The base velocity

  • joint_velocities (np.ndarray) – The joint velocities

Returns:

The Jacobian derivative relative to the frame

Return type:

Jdot (np.ndarray)

CoM_position(base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Returns the CoM position

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

  • joint_positions (np.ndarray) – The joints position

Returns:

The CoM position

Return type:

CoM (np.ndarray)

CoM_jacobian(base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Returns the CoM Jacobian

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

  • joint_positions (np.ndarray) – The joints position

Returns:

The CoM Jacobian

Return type:

Jcom (np.ndarray)

bias_force(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray) numpy.ndarray[source]#

Returns the bias force of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)

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

  • joint_positions (np.ndarray) – The joints position

  • base_velocity (np.ndarray) – The base velocity

  • joint_velocities (np.ndarray) – The joint velocities

Returns:

the bias force

Return type:

h (np.ndarray)

coriolis_term(base_transform: numpy.ndarray, joint_positions: numpy.ndarray, base_velocity: numpy.ndarray, joint_velocities: numpy.ndarray) numpy.ndarray[source]#

Returns the coriolis term of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)

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

  • joint_positions (np.ndarray) – The joints position

  • base_velocity (np.ndarray) – The base velocity

  • joint_velocities (np.ndarray) – The joint velocities

Returns:

the Coriolis term

Return type:

C (np.ndarray)

gravity_term(base_transform: numpy.ndarray, joint_positions: numpy.ndarray) numpy.ndarray[source]#

Returns the gravity term of the floating-base dynamics equation, using a reduced RNEA (no acceleration and external forces)

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

  • joint_positions (np.ndarray) – The joints position

Returns:

the gravity term

Return type:

G (np.ndarray)

get_total_mass() float[source]#

Returns the total mass of the robot

Returns:

The total mass

Return type:

mass