adam.parametric.numpy package#

Submodules#

adam.parametric.numpy.computations_parametric module#

class adam.parametric.numpy.computations_parametric.KinDynComputationsParametric(urdfstring: str, joints_name_list: list, links_name_list: list, root_link: str = None, gravity: array = array([0., 0., -9.80665, 0., 0., 0.]))[source]#

Bases: object

This is a small class that retrieves robot quantities using NumPy for Floating Base systems. This is parametric w.r.t the link length and densities.

set_frame_velocity_representation(representation: Representations) None[source]#

Sets the representation of the velocity of the frames

Parameters:

representation (Representations) – The representation of the velocity

mass_matrix(base_transform: ndarray, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

Mass Matrix

Return type:

M (np.ndarray)

centroidal_momentum_matrix(base_transform: ndarray, s: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

Centroidal Momentum matrix

Return type:

Jcc (np.ndarray)

forward_kinematics(frame: str, base_transform: ndarray, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The fk represented as Homogenous transformation matrix

Return type:

T_fk (np.ndarray)

jacobian(frame: str, base_transform: ndarray, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The Jacobian relative to the frame

Return type:

J_tot (np.ndarray)

relative_jacobian(frame: str, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The Jacobian between the root and the frame

Return type:

J (np.ndarray)

jacobian_dot(frame: str, base_transform: ndarray, joint_positions: ndarray, base_velocity: ndarray, joint_velocities: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The Jacobian derivative relative to the frame

Return type:

Jdot (np.ndarray)

CoM_position(base_transform: ndarray, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The CoM position

Return type:

CoM (np.ndarray)

bias_force(base_transform: ndarray, joint_positions: ndarray, base_velocity: ndarray, joint_velocities: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

the bias force

Return type:

h (np.ndarray)

coriolis_term(base_transform: ndarray, joint_positions: ndarray, base_velocity: ndarray, joint_velocities: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

the Coriolis term

Return type:

C (np.ndarray)

gravity_term(base_transform: ndarray, joint_positions: ndarray, length_multiplier: ndarray, densities: ndarray) 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

  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

the gravity term

Return type:

G (np.ndarray)

get_total_mass(length_multiplier: ndarray, densities: ndarray) float[source]#

Returns the total mass of the robot

Parameters:
  • length_multiplier (np.ndarray) – The length multiplier of the parametrized links

  • densities (np.ndarray) – The densities of the parametrized links

Returns:

The total mass

Return type:

mass

get_original_densities() list[float][source]#

Returns the original densities of the parametric links

Returns:

The original densities of the parametric links

Return type:

densities