adam.casadi#

Submodules#

Classes#

CasadiLike

Wrapper class for CasADi SX/DM with ArrayLike ops.

KinDynComputations

Class that retrieves robot quantities using CasADi for Floating Base systems.

Package Contents#

class adam.casadi.CasadiLike[source]#

Bases: adam.core.spatial_math.ArrayLike

Wrapper class for CasADi SX/DM with ArrayLike ops.

array: casadi.SX | casadi.DM#
__matmul__(other: CasadiLike) CasadiLike[source]#
__rmatmul__(other: CasadiLike) CasadiLike[source]#
__mul__(other: CasadiLike) CasadiLike[source]#
__rmul__(other: CasadiLike) CasadiLike[source]#
__truediv__(other: CasadiLike) CasadiLike[source]#
__add__(other: CasadiLike) CasadiLike[source]#
__radd__(other: CasadiLike) CasadiLike[source]#
__sub__(other: CasadiLike) CasadiLike[source]#
__rsub__(other: CasadiLike) CasadiLike[source]#
__neg__() CasadiLike[source]#
__getitem__(idx) CasadiLike[source]#
property shape: tuple[int, Ellipsis]#
property ndim: int#
property T: CasadiLike#

Transpose of the array

Type:

Returns

class adam.casadi.KinDynComputations(urdfstring: str, joints_name_list: list = None, root_link: str = None, 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]#

Bases: adam.model.kindyn_mixin.KinDynFactoryMixin

Class that retrieves robot quantities using CasADi for Floating Base systems.

rbdalgos#
NDoF#
g#
f_opts#
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 position

Returns:

The CoM position

Return type:

CoM (casADi function)

CoM_jacobian_fun() casadi.Function[source]#

Returns the CoM Jacobian

Returns:

The CoM Jacobian

Return type:

J_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, joint_positions: casadi.SX)[source]#

Returns the Mass Matrix functions computed the CRBA

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

  • joint_positions (cs.SX) – The joints position

Returns:

Mass Matrix

Return type:

M (cs.SX)

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

Returns the Centroidal Momentum Matrix functions computed the CRBA

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

  • joint_positions (cs.SX) – The joints position

Returns:

Centroidal Momentum matrix

Return type:

Jcc (cs.SX)

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

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

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

  • joint_positions (cs.SX) – The joints position

Returns:

The Jacobian between the root and the frame

Return type:

J (cs.SX)

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

Returns the Jacobian derivative relative to the specified frame

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

  • base_transform (cs.SX) – The homogenous transform from base to world frame

  • joint_positions (cs.SX) – The joints position

  • base_velocity (cs.SX) – The base velocity

  • joint_velocities (cs.SX) – The joint velocities

Returns:

The Jacobian derivative relative to the frame

Return type:

Jdot (cs.SX)

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

Computes the forward kinematics relative to the specified frame

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

  • base_transform (cs.SX) – The homogenous transform from base to world frame

  • joint_positions (cs.SX) – The joints position

Returns:

The fk represented as Homogenous transformation matrix

Return type:

H (cs.SX)

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

Returns the Jacobian relative to the specified frame

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

  • s (cs.SX) – 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 (cs.SX)

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

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

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

  • joint_positions (cs.SX) – The joints position

  • base_velocity (cs.SX) – The base velocity

  • joint_velocities (cs.SX) – The joints velocity

Returns:

the bias force

Return type:

h (cs.SX)

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

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

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

  • joint_positions (cs.SX) – The joints position

  • base_velocity (cs.SX) – The base velocity

  • joint_velocities (cs.SX) – The joints velocity

Returns:

the Coriolis term

Return type:

C (cs.SX)

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

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

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

  • joint_positions (cs.SX) – The joints position

Returns:

the gravity term

Return type:

G (cs.SX)

aba(base_transform: casadi.SX, joint_positions: casadi.SX, base_velocity: casadi.SX, joint_velocities: casadi.SX, joint_torques: casadi.SX, external_wrenches: dict[str, casadi.SX] | None = None) casadi.SX[source]#

Featherstone Articulated-Body Algorithm (floating base, O(n)).

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

  • joint_positions (cs.SX) – The joints position

  • base_velocity (cs.SX) – The base velocity

  • joint_velocities (cs.SX) – The joint velocities

  • joint_torques (cs.SX) – The joint torques

  • external_wrenches (dict[str, cs.SX], optional) – External wrenches applied to the robot. Defaults to None.

Returns:

The base acceleration and the joint accelerations

Return type:

cs.SX

aba_fun() casadi.Function[source]#

Returns the Articulated Body Algorithm function for forward dynamics

Returns:

The joint accelerations and base acceleration

Return type:

qdd (casADi function)

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

Returns the CoM position

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

  • joint_positions (cs.SX) – The joints position

Returns:

The CoM position

Return type:

CoM (cs.SX)

CoM_jacobian(base_transform: casadi.SX, joint_positions: casadi.SX) casadi.SX[source]#

Returns the CoM Jacobian

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

  • joint_positions (cs.SX) – The joints position

Returns:

The CoM Jacobian

Return type:

J_com (cs.SX)