adam.parametric.casadi#
Submodules#
Classes#
This is a small class that retrieves robot quantities represented in a symbolic fashion using CasADi for Floating Base systems. |
Package Contents#
- class adam.parametric.casadi.KinDynComputationsParametric(urdfstring: str, joints_name_list: list, links_name_list: list, 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')))[source]#
This is a small class that retrieves robot quantities represented in a symbolic fashion using CasADi for Floating Base systems. This is parametric w.r.t the link length and densities.
- densities#
- length_multiplier#
- links_name_list#
- 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:
T_fk (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)
- 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)