adam.casadi.computations#

Classes#

KinDynComputations

This is a small class that retrieves robot quantities represented in a symbolic fashion using CasADi

Module Contents#

class adam.casadi.computations.KinDynComputations(urdfstring: str, joints_name_list: list = None, root_link: str = 'root_link', gravity: numpy.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'), cse=True))[source]#

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.

math[source]#
factory[source]#
model[source]#
rbdalgos[source]#
NDoF[source]#
g[source]#
f_opts[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_fun() casadi.Function[source]#

Returns the Mass Matrix functions computed the CRBA

Returns:

Mass Matrix

Return type:

M (casADi function)

centroidal_momentum_matrix_fun() casadi.Function[source]#

Returns the Centroidal Momentum Matrix functions computed the CRBA

Returns:

Centroidal Momentum matrix

Return type:

Jcc (casADi function)

forward_kinematics_fun(frame: str) casadi.Function[source]#

Computes the forward kinematics relative to the specified frame

Parameters:

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

Returns:

The fk represented as Homogenous transformation matrix

Return type:

H (casADi function)

jacobian_fun(frame: str) casadi.Function[source]#

Returns the Jacobian relative to the specified frame

Parameters:

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

Returns:

The Jacobian relative to the frame

Return type:

J_tot (casADi function)

relative_jacobian_fun(frame: str) casadi.Function[source]#

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

Parameters:

frame (str) – The tip of the chain

Returns:

The Jacobian between the root and the frame

Return type:

J (casADi function)

jacobian_dot_fun(frame: str) casadi.Function[source]#

Returns the Jacobian derivative relative to the specified frame

Parameters:

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

Returns:

The Jacobian derivative relative to the frame

Return type:

J_dot (casADi function)

CoM_position_fun() casadi.Function[source]#

Returns the CoM positon

Returns:

The CoM position

Return type:

CoM (casADi function)

bias_force_fun() casadi.Function[source]#

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

Returns:

the bias force

Return type:

h (casADi function)

coriolis_term_fun() casadi.Function[source]#

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

Returns:

the Coriolis term

Return type:

C (casADi function)

gravity_term_fun() casadi.Function[source]#

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

Returns:

the gravity term

Return type:

G (casADi function)

get_total_mass() float[source]#

Returns the total mass of the robot

Returns:

The total mass

Return type:

mass

mass_matrix(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM)[source]#

Returns the Mass Matrix functions computed the CRBA

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

Mass Matrix

Return type:

M (Union[cs.SX, cs.DM])

centroidal_momentum_matrix(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM)[source]#

Returns the Centroidal Momentum Matrix functions computed the CRBA

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

Centroidal Momentum matrix

Return type:

Jcc (Union[cs.SX, cs.DM])

relative_jacobian(frame: str, joint_positions: casadi.SX | casadi.DM)[source]#

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

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

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

The Jacobian between the root and the frame

Return type:

J (Union[cs.SX, cs.DM])

jacobian_dot(frame: str, base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM, base_velocity: casadi.SX | casadi.DM, joint_velocities: casadi.SX | casadi.DM) casadi.SX | casadi.DM[source]#

Returns the Jacobian derivative relative to the specified frame

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

  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

  • base_velocity (Union[cs.SX, cs.DM]) – The base velocity in mixed representation

  • joint_velocities (Union[cs.SX, cs.DM]) – The joint velocities

Returns:

The Jacobian derivative relative to the frame

Return type:

Jdot (Union[cs.SX, cs.DM])

forward_kinematics(frame: str, base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM)[source]#

Computes the forward kinematics relative to the specified frame

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

  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

The fk represented as Homogenous transformation matrix

Return type:

H (Union[cs.SX, cs.DM])

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

Returns the Jacobian relative to the specified frame

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • s (Union[cs.SX, cs.DM]) – The joints position

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

Returns:

The Jacobian relative to the frame

Return type:

J_tot (Union[cs.SX, cs.DM])

bias_force(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM, base_velocity: casadi.SX | casadi.DM, joint_velocities: casadi.SX | casadi.DM) casadi.SX | casadi.DM[source]#

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

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

  • base_velocity (Union[cs.SX, cs.DM]) – The base velocity in mixed representation

  • joint_velocities (Union[cs.SX, cs.DM]) – The joints velocity

Returns:

the bias force

Return type:

h (Union[cs.SX, cs.DM])

coriolis_term(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM, base_velocity: casadi.SX | casadi.DM, joint_velocities: casadi.SX | casadi.DM) casadi.SX | casadi.DM[source]#

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

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

  • base_velocity (Union[cs.SX, cs.DM]) – The base velocity in mixed representation

  • joint_velocities (Union[cs.SX, cs.DM]) – The joints velocity

Returns:

the Coriolis term

Return type:

C (Union[cs.SX, cs.DM])

gravity_term(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM) casadi.SX | casadi.DM[source]#

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

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

the gravity term

Return type:

G (Union[cs.SX, cs.DM])

CoM_position(base_transform: casadi.SX | casadi.DM, joint_positions: casadi.SX | casadi.DM) casadi.SX | casadi.DM[source]#

Returns the CoM positon

Parameters:
  • base_transform (Union[cs.SX, cs.DM]) – The homogenous transform from base to world frame

  • joint_positions (Union[cs.SX, cs.DM]) – The joints position

Returns:

The CoM position

Return type:

CoM (Union[cs.SX, cs.DM])