Rigid Body Dynamics Algorithms

Rigid Body Dynamics Algorithms#

This module provides a set of algorithms for rigid body dynamics.

aba(model, *, base_position, ...[, ...])

Compute forward dynamics using the Articulated Body Algorithm (ABA).

collidable_points

contacts.soft

contacts.rigid

contacts.relaxed_rigid

crba(model, *, joint_positions)

Compute the free-floating mass matrix using the Composite Rigid-Body Algorithm (CRBA).

forward_kinematics

jacobian(model, *, link_index, joint_positions)

Compute the free-floating Jacobian of a link.

utils

Collision Detection#

jaxsim.rbda.collidable_points.collidable_points_pos_vel(model, *, link_transforms, link_velocities)[source]

Compute the position and linear velocity of the enabled collidable points in the world frame.

Parameters:
  • model (JaxSimModel) – The model to consider.

  • link_transforms (Array) – The transforms from the world frame to each link.

  • link_velocities (Array) – The linear and angular velocities of each link.

Return type:

tuple[Array, Array]

Returns:

A tuple containing the position and linear velocity of the enabled collidable points.

Contact Models#

class jaxsim.rbda.contacts.soft.SoftContacts[source]

Soft contacts model.

classmethod build(model=None, **kwargs)[source]

Create a SoftContacts instance with specified parameters.

Parameters:
  • model (JaxSimModel | None) – The robot model considered by the contact model. If passed, it is used to estimate good default parameters.

  • **kwargs – Additional parameters to pass to the contact model.

Return type:

Self

Returns:

The SoftContacts instance.

static compute_contact_force(position, velocity, tangential_deformation, parameters, terrain)[source]

Compute the contact force.

Parameters:
  • position (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The position of the collidable point.

  • velocity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The velocity of the collidable point.

  • tangential_deformation (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The material deformation of the collidable point.

  • parameters (SoftContactsParams) – The parameters of the soft contacts model.

  • terrain (Terrain) – The terrain model.

Return type:

tuple[Array, Array]

Returns:

A tuple containing the computed contact force and the derivative of the material deformation.

static compute_contact_forces(model, data)[source]

Compute the contact forces.

Parameters:
  • model (JaxSimModel) – The model to consider.

  • data (JaxSimModelData) – The data of the considered model.

Return type:

tuple[Array, dict[str, dict[Hashable, TypeVar(PyTree)] | list[TypeVar(PyTree)] | tuple[TypeVar(PyTree)] | Array | Any | None]]

Returns:

A tuple containing as first element the computed contact forces, and as second element a dictionary with derivative of the material deformation.

static hunt_crossley_contact_model(position, velocity, tangential_deformation, terrain, K, D, mu, p=0.5, q=0.5)[source]

Compute the contact force using the Hunt/Crossley model.

Parameters:
  • position (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The position of the collidable point.

  • velocity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The velocity of the collidable point.

  • tangential_deformation (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The material deformation of the collidable point.

  • terrain (Terrain) – The terrain model.

  • K (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The stiffness parameter.

  • D (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The damping parameter of the soft contacts model.

  • mu (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The static friction coefficient.

  • p (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The exponent p corresponding to the damping-related non-linearity of the Hunt/Crossley model.

  • q (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The exponent q corresponding to the spring-related non-linearity of the Hunt/Crossley model

Return type:

tuple[Array, Array]

Returns:

A tuple containing the computed contact force and the derivative of the material deformation.

update_contact_state(old_contact_state)[source]

Update the contact state.

Parameters:
  • old_contact_state (dict[str, Array]) – The old contact state.

  • self (type[Self])

Return type:

dict[str, Array]

Returns:

The updated contact state.

update_velocity_after_impact(model, data)[source]

Update the velocity after an impact.

Parameters:
  • model (JaxSimModel) – The robot model considered by the contact model.

  • data (JaxSimModelData) – The data of the considered model.

  • self (type[Self])

Return type:

JaxSimModelData

Returns:

The updated data of the considered model.

classmethod zero_state_variables(model)[source]

Build zero state variables of the contact model.

Return type:

dict[str, Array]

Parameters:

model (JaxSimModel)

class jaxsim.rbda.contacts.soft.SoftContactsParams(K=<factory>, D=<factory>, mu=<factory>, p=<factory>, q=<factory>)[source]

Parameters of the soft contacts model.

Parameters:
  • K (Array)

  • D (Array)

  • mu (Array)

  • p (Array)

  • q (Array)

classmethod build(*, K=1000000.0, D=2000, mu=0.5, p=0.5, q=0.5, **kwargs)[source]

Create a SoftContactsParams instance with specified parameters.

Parameters:
  • K (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The stiffness parameter.

  • D (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The damping parameter of the soft contacts model.

  • mu (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The static friction coefficient.

  • p (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The exponent p corresponding to the damping-related non-linearity of the Hunt/Crossley model.

  • q (Union[float, Array, ndarray, bool, number, bool, int, complex]) – The exponent q corresponding to the spring-related non-linearity of the Hunt/Crossley model

  • **kwargs – Additional parameters to pass to the contact model.

Return type:

Self

Returns:

A SoftContactsParams instance with the specified parameters.

valid()[source]

Check if the parameters are valid.

Return type:

Union[bool, Array, ndarray, bool, number, int, float, complex]

Returns:

True if the parameters are valid, False otherwise.

class jaxsim.rbda.contacts.rigid.RigidContacts(*, regularization_delassus=1e-06, _solver_options_keys=('solver_tol',), _solver_options_values=(0.001,))[source]

Rigid contacts model.

Parameters:
  • regularization_delassus (Annotated[float, '__jax_dataclasses_static_field__'])

  • _solver_options_keys (Annotated[tuple[str, ...], '__jax_dataclasses_static_field__'])

  • _solver_options_values (Annotated[tuple[Any, ...], '__jax_dataclasses_static_field__'])

classmethod build(regularization_delassus=None, solver_options=None, **kwargs)[source]

Create a RigidContacts instance with specified parameters.

Parameters:
  • regularization_delassus (Union[float, Array, ndarray, bool, number, bool, int, complex, None]) – The regularization term to add to the diagonal of the Delassus matrix.

  • solver_options (dict[str, Any] | None) – The options to pass to the QP solver.

  • **kwargs – Extra arguments which are ignored.

Return type:

Self

Returns:

The RigidContacts instance.

compute_contact_forces(model, data, *, link_forces=None, joint_force_references=None)[source]

Compute the contact forces.

Parameters:
  • model (JaxSimModel) – The model to consider.

  • data (JaxSimModelData) – The data of the considered model.

  • link_forces (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – Optional (n_links, 6) matrix of external forces acting on the links, expressed in the same representation of data.

  • joint_force_references (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – Optional (n_joints,) vector of joint forces.

Return type:

tuple[Array, dict[str, dict[Hashable, TypeVar(PyTree)] | list[TypeVar(PyTree)] | tuple[TypeVar(PyTree)] | Array | Any | None]]

Returns:

A tuple containing as first element the computed contact forces.

static compute_impact_velocity(inactive_collidable_points, M, J_WC, generalized_velocity)[source]

Return the new velocity of the system after a potential impact.

Parameters:
  • inactive_collidable_points (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The activation state of the collidable points.

  • M (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The mass matrix of the system (in mixed representation).

  • J_WC (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The Jacobian matrix of the collidable points (in mixed representation).

  • generalized_velocity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple]) – The generalized velocity of the system.

Return type:

Array

Note

The mass matrix M, the Jacobian J_WC, and the generalized velocity generalized_velocity must be expressed in the same velocity representation.

property solver_options: dict[str, Any]

Get the solver options as a dictionary.

update_contact_state(old_contact_state)[source]

Update the contact state.

Parameters:
  • old_contact_state (dict[str, Array]) – The old contact state.

  • self (type[Self])

Return type:

dict[str, Array]

Returns:

The updated contact state.

update_velocity_after_impact(model, data)[source]

Update the velocity after an impact.

Parameters:
  • model (JaxSimModel) – The robot model considered by the contact model.

  • data (JaxSimModelData) – The data of the considered model.

  • self (type[Self])

Return type:

JaxSimModelData

Returns:

The updated data of the considered model.

class jaxsim.rbda.contacts.rigid.RigidContactsParams(mu=<factory>, K=<factory>, D=<factory>)[source]

Parameters of the rigid contacts model.

Parameters:
  • mu (Array)

  • K (Array)

  • D (Array)

classmethod build(*, mu=None, K=None, D=None, **kwargs)[source]

Create a RigidContactParams instance.

Return type:

Self

Parameters:
  • mu (float | Array | ndarray | bool | number | bool | int | complex | None)

  • K (float | Array | ndarray | bool | number | bool | int | complex | None)

  • D (float | Array | ndarray | bool | number | bool | int | complex | None)

valid()[source]

Check if the parameters are valid.

Return type:

Union[bool, Array, ndarray, bool, number, int, float, complex]

class jaxsim.rbda.contacts.relaxed_rigid.RelaxedRigidContacts(*, _solver_options_keys=('tol', 'maxiter', 'memory_size', 'scale_init_precond'), _solver_options_values=(1e-06, 50, 10, False))[source]

Relaxed rigid contacts model.

Parameters:
  • _solver_options_keys (Annotated[tuple[str, ...], '__jax_dataclasses_static_field__'])

  • _solver_options_values (Annotated[tuple[Any, ...], '__jax_dataclasses_static_field__'])

classmethod build(solver_options=None, **kwargs)[source]

Create a RelaxedRigidContacts instance with specified parameters.

Parameters:
  • solver_options (dict[str, Any] | None) – The options to pass to the L-BFGS solver.

  • **kwargs – The parameters of the relaxed rigid contacts model.

Return type:

Self

Returns:

The RelaxedRigidContacts instance.

compute_contact_forces(model, data, *, link_forces=None, joint_force_references=None)[source]

Compute the contact forces.

Parameters:
  • model (JaxSimModel) – The model to consider.

  • data (JaxSimModelData) – The data of the considered model.

  • link_forces (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – Optional (n_links, 6) matrix of external forces acting on the links, expressed in the same representation of data.

  • joint_force_references (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – Optional (n_joints,) vector of joint forces.

Return type:

tuple[Array, dict[str, dict[Hashable, TypeVar(PyTree)] | list[TypeVar(PyTree)] | tuple[TypeVar(PyTree)] | Array | Any | None]]

Returns:

A tuple containing as first element the computed contact forces in inertial representation.

property solver_options: dict[str, Any]

Get the solver options.

update_contact_state(old_contact_state)[source]

Update the contact state.

Parameters:
  • old_contact_state (dict[str, Array]) – The old contact state.

  • self (type[Self])

Return type:

dict[str, Array]

Returns:

The updated contact state.

update_velocity_after_impact(model, data)[source]

Update the velocity after an impact.

Parameters:
  • model (JaxSimModel) – The robot model considered by the contact model.

  • data (JaxSimModelData) – The data of the considered model.

  • self (type[Self])

Return type:

JaxSimModelData

Returns:

The updated data of the considered model.

class jaxsim.rbda.contacts.relaxed_rigid.RelaxedRigidContactsParams(time_constant=0.01, damping_coefficient=1.0, d_min=0.9, d_max=0.95, width=0.0001, midpoint=0.1, power=1.0, K=<factory>, D=<factory>, mu=<factory>)[source]

Parameters of the relaxed rigid contacts model.

Parameters:
  • time_constant (Array)

  • damping_coefficient (Array)

  • d_min (Array)

  • d_max (Array)

  • width (Array)

  • midpoint (Array)

  • power (Array)

  • K (Array)

  • D (Array)

  • mu (Array)

classmethod build(*, time_constant=None, damping_coefficient=None, d_min=None, d_max=None, width=None, midpoint=None, power=None, K=None, D=None, mu=None, **kwargs)[source]

Create a RelaxedRigidContactsParams instance.

Return type:

Self

Parameters:
  • time_constant (float | Array | ndarray | bool | number | bool | int | complex | None)

  • damping_coefficient (float | Array | ndarray | bool | number | bool | int | complex | None)

  • d_min (float | Array | ndarray | bool | number | bool | int | complex | None)

  • d_max (float | Array | ndarray | bool | number | bool | int | complex | None)

  • width (float | Array | ndarray | bool | number | bool | int | complex | None)

  • midpoint (float | Array | ndarray | bool | number | bool | int | complex | None)

  • power (float | Array | ndarray | bool | number | bool | int | complex | None)

  • K (float | Array | ndarray | bool | number | bool | int | complex | None)

  • D (float | Array | ndarray | bool | number | bool | int | complex | None)

  • mu (float | Array | ndarray | bool | number | bool | int | complex | None)

valid()[source]

Check if the parameters are valid.

Return type:

Union[bool, Array, ndarray, bool, number, int, float, complex]

Utilities#

jaxsim.rbda.utils.process_inputs(model, *, base_position=None, base_quaternion=None, joint_positions=None, base_linear_velocity=None, base_angular_velocity=None, joint_velocities=None, base_linear_acceleration=None, base_angular_acceleration=None, joint_accelerations=None, joint_forces=None, link_forces=None, standard_gravity=None)[source]

Adjust the inputs to rigid-body dynamics algorithms.

Parameters:
  • model (JaxSimModel) – The model to consider.

  • base_position (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The position of the base link.

  • base_quaternion (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The quaternion of the base link.

  • joint_positions (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The positions of the joints.

  • base_linear_velocity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The linear velocity of the base link.

  • base_angular_velocity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The angular velocity of the base link.

  • joint_velocities (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The velocities of the joints.

  • base_linear_acceleration (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The linear acceleration of the base link.

  • base_angular_acceleration (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The angular acceleration of the base link.

  • joint_accelerations (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The accelerations of the joints.

  • joint_forces (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The forces applied to the joints.

  • link_forces (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The forces applied to the links.

  • standard_gravity (Union[Array, ndarray, bool, number, bool, int, float, complex, tuple, None]) – The standard gravity constant.

Return type:

tuple[Array, Array, Array, Array, Array, Array, Array, Array, Array, Array]

Returns:

The adjusted inputs.