adam.parametric.jax package#
Submodules#
adam.parametric.jax.computations_parametric module#
- class adam.parametric.jax.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.], dtype=float32))[source]#
Bases:
object
This is a small class that retrieves robot quantities using Jax 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: array, joint_positions: array, length_multiplier: array, densities: array)[source]#
Returns the Mass Matrix functions computed the CRBA
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
Mass Matrix
- Return type:
M (jnp.array)
- centroidal_momentum_matrix(base_transform: array, joint_positions: array, length_multiplier: array, densities: array)[source]#
Returns the Centroidal Momentum Matrix functions computed the CRBA
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
Centroidal Momentum matrix
- Return type:
Jcc (jnp.array)
- relative_jacobian(frame: str, joint_positions: array, length_multiplier: array, densities: array)[source]#
Returns the Jacobian between the root link and a specified frame frames
- Parameters:
frame (str) – The tip of the chain
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
The Jacobian between the root and the frame
- Return type:
J (jnp.array)
- jacobian_dot(frame: str, base_transform: array, joint_positions: array, base_velocity: array, joint_velocities: array, length_multiplier: array, densities: array) array [source]#
Returns the Jacobian derivative relative to the specified frame
- Parameters:
frame (str) – The frame to which the jacobian will be computed
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
base_velocity (jnp.array) – The base velocity
joint_velocities (jnp.array) – The joint velocities
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
The Jacobian derivative relative to the frame
- Return type:
Jdot (jnp.array)
- forward_kinematics(frame: str, base_transform: array, joint_positions: array, length_multiplier: array, densities: array)[source]#
Computes the forward kinematics relative to the specified frame
- Parameters:
frame (str) – The frame to which the fk will be computed
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
The fk represented as Homogenous transformation matrix
- Return type:
T_fk (jnp.array)
- jacobian(frame: str, base_transform, joint_positions, length_multiplier: array, densities: array)[source]#
Returns the Jacobian relative to the specified frame
Args
frame (str): The frame to which the jacobian will be computed base_transform (jnp.array): The homogenous transform from base to world frame s (jnp.array): The joints position length_multiplier (jnp.array): The length multiplier of the parametrized links densities (jnp.array): The densities of the parametrized links
- Returns:
The Jacobian relative to the frame
- Return type:
J_tot (jnp.array)
- bias_force(base_transform: array, joint_positions: array, base_velocity: array, s_dot: array, length_multiplier: array, densities: array) array [source]#
Returns the bias force of the floating-base dynamics ejoint_positionsuation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
base_velocity (jnp.array) – The base velocity
s_dot (jnp.array) – The joints velocity
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
the bias force
- Return type:
h (jnp.array)
- coriolis_term(base_transform: array, joint_positions: array, base_velocity: array, s_dot: array, length_multiplier: array, densities: array) array [source]#
Returns the coriolis term of the floating-base dynamics ejoint_positionsuation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
base_velocity (jnp.array) – The base velocity
s_dot (jnp.array) – The joints velocity
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
the Coriolis term
- Return type:
C (jnp.array)
- gravity_term(base_transform: array, joint_positions: array, length_multiplier: array, densities: array) array [source]#
Returns the gravity term of the floating-base dynamics ejoint_positionsuation, using a reduced RNEA (no acceleration and external forces)
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
the gravity term
- Return type:
G (jnp.array)
- CoM_position(base_transform: array, joint_positions: array, length_multiplier: array, densities: array) array [source]#
Returns the CoM position
- Parameters:
base_transform (jnp.array) – The homogenous transform from base to world frame
joint_positions (jnp.array) – The joints position
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
The CoM position
- Return type:
com (jnp.array)
- get_total_mass(length_multiplier: array, densities: array) float [source]#
Returns the total mass of the robot
- Parameters:
length_multiplier (jnp.array) – The length multiplier of the parametrized links
densities (jnp.array) – The densities of the parametrized links
- Returns:
The total mass
- Return type:
mass