Rigid Body Dynamics Algorithms#
This module provides a set of algorithms for rigid body dynamics.
|
Compute forward dynamics using the Articulated Body Algorithm (ABA). |
|
Compute the free-floating mass matrix using the Composite Rigid-Body Algorithm (CRBA). |
|
Compute the forward kinematics of a specific link. |
|
Compute the free-floating Jacobian of a link. |
Collision Detection#
- jaxsim.rbda.collidable_points.collidable_points_pos_vel(model, *, base_position, base_quaternion, joint_positions, base_linear_velocity, base_angular_velocity, joint_velocities)[source]
Compute the position and linear velocity of collidable points in the world frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.base_position (
Array
) – The position of the base link.base_quaternion (
Array
) – The quaternion of the base link.joint_positions (
Array
) – The positions of the joints.base_linear_velocity (
Array
) – The linear velocity of the base link in inertial-fixed representation.base_angular_velocity (
Array
) – The angular velocity of the base link in inertial-fixed representation.joint_velocities (
Array
) – The velocities of the joints.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the position and linear velocity of collidable points.
Contact Models#
- class jaxsim.rbda.contacts.soft.SoftContacts(parameters=<factory>, terrain=<factory>)[source]
Soft contacts model.
- Parameters:
parameters (SoftContactsParams)
terrain (Annotated[Terrain, '__jax_dataclasses_static_field__'])
- compute_contact_forces(position, velocity, tangential_deformation)[source]
Compute the contact forces and material deformation rate.
- Parameters:
position (
Array
) – The position of the collidable point.velocity (
Array
) – The linear velocity of the collidable point.tangential_deformation (
Array
) – The tangential deformation.
- Return type:
tuple
[Array
,tuple
[Array
]]- Returns:
A tuple containing the contact force and material deformation rate.
- class jaxsim.rbda.contacts.soft.SoftContactsParams(K=<factory>, D=<factory>, mu=<factory>)[source]
Parameters of the soft contacts model.
- Parameters:
K (Array)
D (Array)
mu (Array)
- static build(K=1000000.0, D=2000, mu=0.5)[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.
- Return type:
SoftContactsParams
- Returns:
A SoftContactsParams instance with the specified parameters.
- static build_default_from_jaxsim_model(model, *, standard_gravity=9.81, static_friction_coefficient=0.5, max_penetration=0.001, number_of_active_collidable_points_steady_state=1, damping_ratio=1.0)[source]
Create a SoftContactsParams instance with good default parameters.
- Parameters:
model (
JaxSimModel
) – The target model.standard_gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The standard gravity constant.static_friction_coefficient (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The static friction coefficient between the model and the terrain.max_penetration (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The maximum penetration depth.number_of_active_collidable_points_steady_state (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The number of contacts supporting the weight of the model in steady state.damping_ratio (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The ratio controlling the damping behavior.
- Return type:
SoftContactsParams
- Returns:
A SoftContactsParams instance with the specified parameters.
Note
The damping_ratio parameter allows to operate on the following conditions: - ξ > 1.0: over-damped - ξ = 1.0: critically damped - ξ < 1.0: under-damped
- valid()[source]
Check if the parameters are valid.
- Return type:
bool
- Returns:
True if the parameters are valid, False otherwise.
- class jaxsim.rbda.contacts.soft.SoftContactsState(tangential_deformation)[source]
Class storing the state of the soft contacts model.
- Parameters:
tangential_deformation (Array)
- tangential_deformation
The matrix of 3D tangential material deformations corresponding to each collidable point.
- static build(tangential_deformation=None, number_of_collidable_points=None)[source]
Create a SoftContactsState.
- Parameters:
tangential_deformation (
Array
|None
) – The matrix of 3D tangential material deformations corresponding to each collidable point.number_of_collidable_points (
int
|None
) – The number of collidable points.
- Return type:
SoftContactsState
- Returns:
A SoftContactsState instance.
- static build_from_jaxsim_model(model=None, tangential_deformation=None)[source]
Build a SoftContactsState from a JaxSimModel.
- Parameters:
model (
JaxSimModel
|None
) – The JaxSimModel associated with the soft contacts state.tangential_deformation (
Array
|None
) – The matrix of 3D tangential material deformations.
- Return type:
SoftContactsState
- Returns:
The SoftContactsState built from the JaxSimModel.
Note
If any of the state components are not provided, they are built from the JaxSimModel and initialized to zero.
- valid(model)[source]
Check if the SoftContactsState is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the SoftContactsState against.- Return type:
bool
- Returns:
True if the soft contacts state is valid for the given JaxSimModel, False otherwise.
- static zero(model)[source]
Build a zero SoftContactsState from a JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel associated with the soft contacts state.- Return type:
SoftContactsState
- Returns:
A zero SoftContactsState instance.
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.