Functional API#
Model#
- class jaxsim.api.model.IntegratorType(*values)[source]
The integrators available for the simulation.
- class jaxsim.api.model.JaxSimModel(model_name, time_step=0.001, terrain=<factory>, gravity=-9.81, contact_model=None, contact_params=None, kin_dyn_parameters=None, integrator=IntegratorType.SemiImplicitEuler, built_from=None, _description=None)[source]
The JaxSim model defining the kinematics and dynamics of a robot.
- Parameters:
model_name (Annotated[str, '__jax_dataclasses_static_field__'])
time_step (float)
terrain (Annotated[Terrain, '__jax_dataclasses_static_field__'])
gravity (Annotated[float, '__jax_dataclasses_static_field__'])
contact_model (Annotated[ContactModel | None, '__jax_dataclasses_static_field__'])
contact_params (Annotated[ContactsParams, '__jax_dataclasses_static_field__'])
kin_dyn_parameters (KinDynParameters | None)
integrator (Annotated[IntegratorType, '__jax_dataclasses_static_field__'])
built_from (Annotated[str | Path | Model | None, '__jax_dataclasses_static_field__'])
_description (Annotated[ModelDescription | None, '__jax_dataclasses_static_field__'])
- base_link()[source]
Return the name of the base link.
- Return type:
str
- Returns:
The name of the base link.
Note
By default, the base link is the root of the kinematic tree.
- classmethod build(model_description, *, model_name=None, time_step=None, terrain=None, contact_model=None, contact_params=None, integrator=None, gravity=9.81)[source]
Build a Model object from an intermediate model description.
- Parameters:
model_description (
ModelDescription
) – The intermediate model description defining the kinematics and dynamics of the model.model_name (
str
|None
) – The name of the model. If not specified, it is read from the description.time_step (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,None
]) – The default time step to consider for the simulation. It can be manually overridden in the function that steps the simulation.terrain (
Terrain
|None
) – The terrain to consider (the default is a flat infinite plane). The optional name of the model overriding the physics model name.contact_model (
ContactModel
|None
) – The contact model to consider. If not specified, a relaxed-constraints rigid contacts model is used.contact_params (
ContactsParams
|None
) – The parameters of the contact model.integrator (
IntegratorType
|None
) – The integrator to use for the simulation.gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The gravity constant.
- Return type:
JaxSimModel
- Returns:
The built Model object.
- classmethod build_from_model_description(model_description, *, model_name=None, time_step=None, terrain=None, contact_model=None, contact_params=None, integrator=None, is_urdf=None, considered_joints=None, gravity=9.81)[source]
Build a Model object from a model description.
- Parameters:
model_description (
str
|Path
|Model
) – A path to an SDF/URDF file, a string containing its content, or a pre-parsed/pre-built rod model.model_name (
str
|None
) – The name of the model. If not specified, it is read from the description.time_step (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,None
]) – The default time step to consider for the simulation. It can be manually overridden in the function that steps the simulation.terrain (
Terrain
|None
) – The terrain to consider (the default is a flat infinite plane).contact_model (
ContactModel
|None
) – The contact model to consider. If not specified, a soft contacts model is used.contact_params (
ContactsParams
|None
) – The parameters of the contact model.integrator (
IntegratorType
|None
) – The integrator to use for the simulation.is_urdf (
bool
|None
) – The optional flag to force the model description to be parsed as a URDF. This is usually automatically inferred.considered_joints (
Sequence
[str
] |None
) – The list of joints to consider. If None, all joints are considered.gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The gravity constant. Normally passed as a positive value.
- Return type:
JaxSimModel
- Returns:
The built Model object.
- property description: ModelDescription
Return the model description.
- dofs()[source]
Return the number of degrees of freedom of the model.
- Return type:
int
- Returns:
The number of degrees of freedom of the model.
Note
We do not yet support multi-DoF joints, therefore this is always equal to the number of joints. In the future, this could be different.
- floating_base()[source]
Return whether the model has a floating base.
- Return type:
bool
- Returns:
True if the model is floating-base, False otherwise.
- frame_names()[source]
Return the names of the frames in the model.
- Return type:
tuple
[str
,...
]- Returns:
The names of the frames in the model.
- joint_names()[source]
Return the names of the joints in the model.
- Return type:
tuple
[str
,...
]- Returns:
The names of the joints in the model.
- link_names()[source]
Return the names of the links in the model.
- Return type:
tuple
[str
,...
]- Returns:
The names of the links in the model.
- name()[source]
Return the name of the model.
- Return type:
str
- Returns:
The name of the model.
- number_of_frames()[source]
Return the number of frames in the model.
- Return type:
int
- Returns:
The number of frames in the model.
- number_of_joints()[source]
Return the number of joints in the model.
- Return type:
int
- Returns:
The number of joints in the model.
- number_of_links()[source]
Return the number of links in the model.
- Return type:
int
- Returns:
The number of links in the model.
Note
The base link is included in the count and its index is always 0.
- jaxsim.api.model.average_velocity(model, data)[source]
Compute the average velocity of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The average velocity of the model computed in the base frame and expressed in the active representation.
- jaxsim.api.model.average_velocity_jacobian(model, data, *, output_vel_repr=None)[source]
Compute the Jacobian of the average velocity of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the jacobian.
- Return type:
Array
- Returns:
The Jacobian of the average centroidal velocity of the model in the desired representation.
- jaxsim.api.model.forward_dynamics(model, data, *, joint_forces=None, link_forces=None, prefer_aba=True)[source]
Compute the forward dynamics of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint forces to consider as a vector of shape (dofs,).link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The link 6D forces consider as a matrix of shape (nL, 6). The frame in which they are expressed must be data.velocity_representation.prefer_aba (
float
) – Whether to prefer the ABA algorithm over the CRB one.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the 6D acceleration in the active representation of the base link and the joint accelerations resulting from the application of the considered joint forces and external forces.
- jaxsim.api.model.forward_dynamics_aba(model, data, *, joint_forces=None, link_forces=None)[source]
Compute the forward dynamics of the model with the ABA algorithm.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint forces to consider as a vector of shape (dofs,).link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The link 6D forces to consider as a matrix of shape (nL, 6). The frame in which they are expressed must be data.velocity_representation.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the 6D acceleration in the active representation of the base link and the joint accelerations resulting from the application of the considered joint forces and external forces.
- jaxsim.api.model.forward_dynamics_crb(model, data, *, joint_forces=None, link_forces=None)[source]
Compute the forward dynamics of the model with the CRB algorithm.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint forces to consider as a vector of shape (dofs,).link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The link 6D forces to consider as a matrix of shape (nL, 6). The frame in which they are expressed must be data.velocity_representation.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the 6D acceleration in the active representation of the base link and the joint accelerations resulting from the application of the considered joint forces and external forces.
Note
Compared to ABA, this method could be significantly slower, especially for models with a large number of degrees of freedom.
- jaxsim.api.model.forward_kinematics(model, data)[source]
Compute the forward kinematics of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The nL x 4 x 4 array containing the stacked homogeneous transformations of the links. The first axis is the link index.
- jaxsim.api.model.free_floating_bias_forces(model, data)[source]
Compute the free-floating bias forces \(h(\mathbf{q}, \boldsymbol{\nu})\) of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The free-floating bias forces of the model.
- jaxsim.api.model.free_floating_coriolis_matrix(model, data)[source]
Compute the free-floating Coriolis matrix of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The free-floating Coriolis matrix of the model.
Note
This function, contrarily to other quantities of the equations of motion, does not exploit any iterative algorithm. Therefore, the computation of the Coriolis matrix may be much slower than other quantities.
- jaxsim.api.model.free_floating_gravity_forces(model, data)[source]
Compute the free-floating gravity forces \(g(\mathbf{q})\) of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The free-floating gravity forces of the model.
- jaxsim.api.model.free_floating_mass_matrix(model, data)[source]
Compute the free-floating mass matrix of the model with the CRBA algorithm.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The free-floating mass matrix of the model.
- jaxsim.api.model.generalized_free_floating_jacobian(model, data, *, output_vel_repr=None)[source]
Compute the free-floating jacobians of all links.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobians.
- Return type:
Array
- Returns:
The (nL, 6, 6+dofs) array containing the stacked free-floating jacobians of the links. The first axis is the link index.
Note
The v-stacked version of the returned Jacobian array together with the flattened 6D forces of the links, are useful to compute the J.T @ f product of the multi-body EoM.
- jaxsim.api.model.generalized_free_floating_jacobian_derivative(model, data, *, output_vel_repr=None)[source]
Compute the free-floating jacobian derivatives of all links.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian derivatives.
- Return type:
Array
- Returns:
The (nL, 6, 6+dofs) array containing the stacked free-floating jacobian derivatives of the links. The first axis is the link index.
- jaxsim.api.model.inverse_dynamics(model, data, *, joint_accelerations=None, base_acceleration=None, link_forces=None)[source]
Compute inverse dynamics with the RNEA algorithm.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_accelerations (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint accelerations to consider as a vector of shape (dofs,).base_acceleration (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The base acceleration to consider as a vector of shape (6,).link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The link 6D forces to consider as a matrix of shape (nL, 6). The frame in which they are expressed must be data.velocity_representation.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the 6D force in the active representation applied to the base to obtain the considered base acceleration, and the joint forces to apply to obtain the considered joint accelerations.
- jaxsim.api.model.kinetic_energy(model, data)[source]
Compute the kinetic energy of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The kinetic energy of the model.
- jaxsim.api.model.link_bias_accelerations(model, data)[source]
Compute the bias accelerations of the links of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The bias accelerations of the links of the model.
Note
This function computes the component of the total 6D acceleration not due to the joint or base acceleration. It is often called \(\dot{J} \boldsymbol{\nu}\).
- jaxsim.api.model.link_spatial_inertia_matrices(model)[source]
Compute the spatial 6D inertia matrices of all links of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.- Return type:
Array
- Returns:
A 3D array containing the stacked spatial 6D inertia matrices of the links.
- jaxsim.api.model.locked_spatial_inertia(model, data)[source]
Compute the locked 6D inertia matrix of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The locked 6D inertia matrix of the model.
- jaxsim.api.model.mechanical_energy(model, data)[source]
Compute the mechanical energy of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The mechanical energy of the model.
- jaxsim.api.model.potential_energy(model, data)[source]
Compute the potential energy of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The potential energy of the model.
- jaxsim.api.model.reduce(model, considered_joints, locked_joint_positions=None)[source]
Reduce the model by lumping together the links connected by removed joints.
- Parameters:
model (
JaxSimModel
) – The model to reduce.considered_joints (
tuple
[str
,...
]) – The sequence of joints to consider.locked_joint_positions (
dict
[str
,Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]] |None
) – A dictionary containing the positions of the joints to be considered in the reduction process. The removed joints in the reduced model will have their position locked to their value of this dictionary. If a joint is not part of the dictionary, its position is set to zero.
- Return type:
JaxSimModel
- jaxsim.api.model.step(model, data, *, link_forces=None, joint_force_references=None)[source]
Perform a simulation step.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.dt – The time step to consider. If not specified, it is read from the model.
link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The 6D forces to apply to the links expressed in same representation of data.joint_force_references (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint force references to consider.
- Return type:
JaxSimModelData
- Returns:
The new data of the model after the simulation step.
Note
In order to reduce the occurrences of frame conversions performed internally, it is recommended to use inertial-fixed velocity representation. This can be particularly useful for automatically differentiated logic.
- jaxsim.api.model.total_mass(model)[source]
Compute the total mass of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.- Return type:
Array
- Returns:
The total mass of the model.
- jaxsim.api.model.total_momentum(model, data)[source]
Compute the total momentum of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The total momentum of the model in the active velocity representation.
- jaxsim.api.model.total_momentum_jacobian(model, data, *, output_vel_repr=None)[source]
Compute the jacobian of the total momentum.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the jacobian.
- Return type:
Array
- Returns:
The jacobian of the total momentum of the model in the active representation.
- jaxsim.api.actuation_model.compute_resultant_torques(model, data, *, joint_force_references=None)[source]
Compute the resultant torques acting on the joints.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_force_references (
Array
|None
) – The joint force references to apply.
- Return type:
Array
- Returns:
The resultant torques acting on the joints.
Data#
- class jaxsim.api.data.JaxSimModelData(_joint_positions, _joint_velocities, _base_quaternion, _base_linear_velocity, _base_angular_velocity, _base_position, _base_transform=None, _joint_transforms=None, _link_transforms=None, _link_velocities=None, contact_state=None, *, velocity_representation=VelRepr.Inertial)[source]
Class storing the state of the physics model dynamics.
- Parameters:
_joint_positions (Array)
_joint_velocities (Array)
_base_quaternion (Array)
_base_linear_velocity (Array)
_base_angular_velocity (Array)
_base_position (Array)
_base_transform (Array)
_joint_transforms (Array)
_link_transforms (Array)
_link_velocities (Array)
contact_state (dict[str, Array])
velocity_representation (Annotated[VelRepr, '__jax_dataclasses_static_field__'])
- joint_positions
The vector of joint positions.
- joint_velocities
The vector of joint velocities.
- base_position
The 3D position of the base link.
- base_quaternion
The quaternion defining the orientation of the base link.
- base_linear_velocity
The linear velocity of the base link in inertial-fixed representation.
- base_angular_velocity
The angular velocity of the base link in inertial-fixed representation.
- base_transform
The base transform.
- joint_transforms
The joint transforms.
- link_transforms
The link transforms.
- link_velocities
The link velocities in inertial-fixed representation.
- property base_orientation: Array
Get the base orientation.
- Returns:
The base orientation.
- property base_position: Array
Get the base position.
- Returns:
The base position.
- property base_quaternion: Array
Get the base quaternion.
- Returns:
The base quaternion.
- property base_transform: Array
Get the base transform.
- Returns:
The base transform.
- property base_velocity: Array
Get the base 6D velocity.
- Returns:
The base 6D velocity in the active representation.
- static build(model, base_position=None, base_quaternion=None, joint_positions=None, base_linear_velocity=None, base_angular_velocity=None, joint_velocities=None, contact_state=None, velocity_representation=VelRepr.Mixed)[source]
Create a JaxSimModelData object with the given state.
- Parameters:
model (
JaxSimModel
) – The model for which to create the state.base_position (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The base position.base_quaternion (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The base orientation as a quaternion.joint_positions (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint positions.base_linear_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The base linear velocity in the selected representation.base_angular_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The base angular velocity in the selected representation.joint_velocities (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint velocities.velocity_representation (
VelRepr
) – The velocity representation to use. It defaults to mixed if not provided.contact_state (
dict
[str
,Array
] |None
) – The optional contact state.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData initialized with the given state.
- property generalized_position: tuple[Array, Array]
Get the generalized position \(\mathbf{q} = ({}^W \mathbf{H}_B, \mathbf{s}) \in \text{SO}(3) \times \mathbb{R}^n\).
- Returns:
A tuple containing the base transform and the joint positions.
- property generalized_velocity: Array
Get the generalized velocity.
\(\boldsymbol{\nu} = (\boldsymbol{v}_{W,B};\, \boldsymbol{\omega}_{W,B};\, \mathbf{s}) \in \mathbb{R}^{6+n}\)
- Returns:
The generalized velocity in the active representation.
- property joint_positions: Array
Get the joint positions.
- Returns:
The joint positions.
- property joint_velocities: Array
Get the joint velocities.
- Returns:
The joint velocities.
- replace(model, joint_positions=None, joint_velocities=None, base_quaternion=None, base_linear_velocity=None, base_angular_velocity=None, base_position=None, *, contact_state=None, validate=False)[source]
Replace the attributes of the JaxSimModelData object.
- Return type:
Self
- Parameters:
model (JaxSimModel)
joint_positions (Array | None)
joint_velocities (Array | None)
base_quaternion (Array | None)
base_linear_velocity (Array | None)
base_angular_velocity (Array | None)
base_position (Array | None)
contact_state (dict[str, Array] | None)
validate (bool)
- reset_base_pose(model, base_pose)[source]
Reset the base pose.
- Parameters:
model (
JaxSimModel
) – The JaxSim model to use.base_pose (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base pose as an SE(3) matrix.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_base_quaternion(model, base_quaternion)[source]
Reset the base quaternion.
- Parameters:
model (
JaxSimModel
) – The JaxSim model to use.base_quaternion (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base orientation as a quaternion.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- valid(model)[source]
Check if the JaxSimModelData is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the JaxSimModelData against.- Return type:
bool
- Returns:
True if the JaxSimModelData is valid for the given model, False otherwise.
- static zero(model, velocity_representation=VelRepr.Mixed)[source]
Create a JaxSimModelData object with zero state.
- Parameters:
model (
JaxSimModel
) – The model for which to create the state.velocity_representation (
VelRepr
) – The velocity representation to use. It defaults to mixed if not provided.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData initialized with zero state.
- jaxsim.api.data.random_model_data(model, *, key=None, velocity_representation=None, base_pos_bounds=((-1, -1, 0.5), 1.0), base_rpy_bounds=(-3.141592653589793, 3.141592653589793), base_rpy_seq='XYZ', joint_pos_bounds=None, base_vel_lin_bounds=(-1.0, 1.0), base_vel_ang_bounds=(-1.0, 1.0), joint_vel_bounds=(-1.0, 1.0))[source]
Randomly generate a JaxSimModelData object.
- Parameters:
model (
JaxSimModel
) – The target model for the random data.key (
Array
|None
) – The random key.velocity_representation (
VelRepr
|None
) – The velocity representation to use.base_pos_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]]) – The bounds for the base position.base_rpy_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]]) – The bounds for the euler angles used to build the base orientation.base_rpy_seq (
str
) – The sequence of axes for rotation (using Rotation from scipy).joint_pos_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]] |None
) – The bounds for the joint positions (reading the joint limits if None).base_vel_lin_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]]) – The bounds for the base linear velocity.base_vel_ang_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]]) – The bounds for the base angular velocity.joint_vel_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,Sequence
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]]]) – The bounds for the joint velocities.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData object with random data.
Contact#
- jaxsim.api.contact.collidable_point_kinematics(model, data)[source]
Compute the position and 3D velocity of the collidable points in the world frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
tuple
[Array
,Array
]- Returns:
The position and velocity of the collidable points in the world frame.
Note
The collidable point velocity is the plain coordinate derivative of the position. If we attach a frame C = (p_C, [C]) to the collidable point, it corresponds to the linear component of the mixed 6D frame velocity.
- jaxsim.api.contact.collidable_point_positions(model, data)[source]
Compute the position of the collidable points in the world frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The position of the collidable points in the world frame.
- jaxsim.api.contact.collidable_point_velocities(model, data)[source]
Compute the 3D velocity of the collidable points in the world frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The 3D velocity of the collidable points.
- jaxsim.api.contact.estimate_good_contact_parameters(model, *, standard_gravity=9.81, static_friction_coefficient=0.5, number_of_active_collidable_points_steady_state=1, damping_ratio=1.0, max_penetration=None)[source]
Estimate good contact parameters.
- Parameters:
model (
JaxSimModel
) – The model to consider.standard_gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The standard gravity acceleration.static_friction_coefficient (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The static friction coefficient.number_of_active_collidable_points_steady_state (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The number of active collidable points in steady state.damping_ratio (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The damping ratio.max_penetration (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,None
]) – The maximum penetration allowed.
- Return type:
SoftContactsParams
|RigidContactsParams
|RelaxedRigidContactsParams
- Returns:
The estimated good contacts parameters.
Note
This is primarily a convenience function for soft-like contact models. However, it provides with some good default parameters also for the other ones.
Note
This method provides a good set of contacts parameters. The user is encouraged to fine-tune the parameters based on the specific application.
- jaxsim.api.contact.estimate_good_soft_contacts_parameters(*args, **kwargs)[source]
Estimate good soft contacts parameters. Deprecated, use estimate_good_contact_parameters instead.
- Return type:
SoftContactsParams
|RigidContactsParams
|RelaxedRigidContactsParams
- jaxsim.api.contact.in_contact(model, data, *, link_names=None)[source]
Return whether the links are in contact with the terrain.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_names (
tuple
[str
,...
] |None
) – The names of the links to consider. If None, all links are considered.
- Return type:
Array
- Returns:
A boolean vector indicating whether the links are in contact with the terrain.
- jaxsim.api.contact.jacobian(model, data, *, output_vel_repr=None)[source]
Return the free-floating Jacobian of the enabled collidable points.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian.
- Return type:
Array
- Returns:
The stacked \(6 \times (6+n)\) free-floating jacobians of the frames associated to the enabled collidable points.
Note
Each collidable point is implicitly associated with a frame \(C = ({}^W p_C, [L])\), where \({}^W p_C\) is the position of the collidable point and \([L]\) is the orientation frame of the link it is rigidly attached to.
- jaxsim.api.contact.jacobian_derivative(model, data, *, output_vel_repr=None)[source]
Compute the derivative of the free-floating jacobian of the enabled collidable points.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian derivative.
- Return type:
Array
- Returns:
The derivative of the \(6 \times (6+n)\) free-floating jacobian of the enabled collidable points.
Note
The input representation of the free-floating jacobian derivative is the active velocity representation.
- jaxsim.api.contact.link_contact_forces(model, data, *, link_forces=None, joint_torques=None)[source]
Compute the 6D contact forces of all links of the model in inertial representation.
- 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
]) – The 6D external forces to apply to the links expressed in inertial representationjoint_torques (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint torques acting on the joints.
- Return type:
tuple
[Array
,dict
[str
,Array
]]- Returns:
A (nL, 6) array containing the stacked 6D contact forces of the links, expressed in inertial representation.
- jaxsim.api.contact.link_forces_from_contact_forces(model, *, contact_forces)[source]
Compute the link forces from the contact forces.
- Parameters:
model (
JaxSimModel
) – The robot model considered by the contact model.contact_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The contact forces computed by the contact model.
- Return type:
Array
- Returns:
The 6D contact forces applied to the links and expressed in the frame of the velocity representation of data.
- jaxsim.api.contact.transforms(model, data)[source]
Return the pose of the enabled collidable points.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The stacked SE(3) matrices of all enabled collidable points.
Note
Each collidable point is implicitly associated with a frame \(C = ({}^W p_C, [L])\), where \({}^W p_C\) is the position of the collidable point and \([L]\) is the orientation frame of the link it is rigidly attached to.
KinDynParameters#
- class jaxsim.api.kin_dyn_parameters.ContactParameters(body=<factory>, point=<factory>, enabled=<factory>)[source]
Class storing the contact parameters of a model.
- Parameters:
body (Annotated[tuple[int, ...], '__jax_dataclasses_static_field__'])
point (Array)
enabled (Annotated[tuple[bool, ...], '__jax_dataclasses_static_field__'])
- body
A tuple of integers representing, for each collidable point, the index of the body (link) to which it is rigidly attached to.
- point
The translations between the link frame and the collidable point, expressed in the coordinates of the parent link frame.
- enabled
A tuple of booleans representing, for each collidable point, whether it is enabled or not in contact models.
Note
Contrarily to LinkParameters and JointParameters, this class is not meant to be created with vmap. This is because the body attribute must be Static.
- static build_from(model_description)[source]
Build a ContactParameters object from a model description.
- Parameters:
model_description (
ModelDescription
) – The model description to consider.- Return type:
ContactParameters
- Returns:
The ContactParameters object.
- property indices_of_enabled_collidable_points: ndarray[tuple[int, ...], dtype[_ScalarType_co]]
Return the indices of the enabled collidable points.
- class jaxsim.api.kin_dyn_parameters.FrameParameters(name=<factory>, body=<factory>, transform=<factory>)[source]
Class storing the frame parameters of a model.
- Parameters:
name (Annotated[tuple[str, ...], '__jax_dataclasses_static_field__'])
body (Annotated[tuple[int, ...], '__jax_dataclasses_static_field__'])
transform (Array)
- name
A tuple of strings defining the frame names.
- body
A vector of integers representing, for each frame, the index of the body (link) to which it is rigidly attached to.
- transform
The transforms of the frames w.r.t. their parent link.
Note
Contrarily to LinkParameters and JointParameters, this class is not meant to be created with vmap. This is because the name attribute must be Static.
- static build_from(model_description)[source]
Build a FrameParameters object from a model description.
- Parameters:
model_description (
ModelDescription
) – The model description to consider.- Return type:
FrameParameters
- Returns:
The FrameParameters object.
- class jaxsim.api.kin_dyn_parameters.JointParameters(index, friction_static, friction_viscous, position_limits_min, position_limits_max, position_limit_spring, position_limit_damper)[source]
Class storing the parameters of a joint.
- Parameters:
index (Array)
friction_static (Array)
friction_viscous (Array)
position_limits_min (Array)
position_limits_max (Array)
position_limit_spring (Array)
position_limit_damper (Array)
- index
The index of the joint.
- friction_static
The static friction of the joint.
- friction_viscous
The viscous friction of the joint.
- position_limits_min
The lower position limit of the joint.
- position_limits_max
The upper position limit of the joint.
- position_limit_spring
The spring constant of the position limit.
- position_limit_damper
The damper constant of the position limit.
Note
This class is used inside KinDynParameters to store the vectorized set of joint parameters.
- static build_from_joint_description(joint_description)[source]
Build a JointParameters object from a joint description.
- Parameters:
joint_description (
JointDescription
) – The joint description to consider.- Return type:
JointParameters
- Returns:
The JointParameters object.
- class jaxsim.api.kin_dyn_parameters.KinDynParameters(link_names, _parent_array, _support_body_array_bool, _motion_subspaces, link_parameters, contact_parameters, frame_parameters, joint_model, joint_parameters)[source]
Class storing the kinematic and dynamic parameters of a model.
- Parameters:
link_names (Annotated[tuple[str], '__jax_dataclasses_static_field__'])
_parent_array (Annotated[tuple[int], '__jax_dataclasses_static_field__'])
_support_body_array_bool (Annotated[tuple[int], '__jax_dataclasses_static_field__'])
_motion_subspaces (Annotated[tuple[float], '__jax_dataclasses_static_field__'])
link_parameters (LinkParameters)
contact_parameters (ContactParameters)
frame_parameters (FrameParameters)
joint_model (JointModel)
joint_parameters (JointParameters | None)
- link_names
The names of the links.
- parent_array
The parent array \(\lambda(i)\) of the model.
- support_body_array_bool
The boolean support parent array \(\kappa_{b}(i)\) of the model.
- link_parameters
The parameters of the links.
- frame_parameters
The parameters of the frames.
- contact_parameters
The parameters of the collidable points.
- joint_model
The joint model of the model.
- joint_parameters
The parameters of the joints.
- static build(model_description)[source]
Construct the kinematic and dynamic parameters of the model.
- Parameters:
model_description (
ModelDescription
) – The parsed model description to consider.- Return type:
KinDynParameters
- Returns:
The kinematic and dynamic parameters of the model.
Note
This class is meant to ease the management of parametric models in an automatic differentiation context.
- joint_transforms(joint_positions, base_transform)[source]
Return the transforms of the joints.
- Parameters:
joint_positions (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The joint positions.base_transform (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The homogeneous matrix defining the base pose.
- Return type:
Array
- Returns:
The stacked transforms \({}^{i} \mathbf{H}_{\lambda(i)}(s)\) of each joint.
- links_spatial_inertia()[source]
Return the spatial inertia of all links of the model.
- Return type:
Array
- Returns:
The spatial inertia of all links of the model.
- property motion_subspaces: Array
Return the motion subspaces \(\mathbf{S}(s)\) of the joints.
- number_of_frames()[source]
Return the number of frames of the model.
- Return type:
int
- Returns:
The number of frames of the model.
- number_of_joints()[source]
Return the number of joints of the model.
- Return type:
int
- Returns:
The number of joints of the model.
- number_of_links()[source]
Return the number of links of the model.
- Return type:
int
- Returns:
The number of links of the model.
- property parent_array: Array
Return the parent array \(\lambda(i)\) of the model.
- set_link_inertia(link_index, inertia)[source]
Set the inertia tensor of a link.
- Parameters:
link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.inertia (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The \(3 \times 3\) inertia tensor of the link.
- Return type:
KinDynParameters
- Returns:
The updated kinematic and dynamic parameters of the model.
- set_link_mass(link_index, mass)[source]
Set the mass of a link.
- Parameters:
link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.mass (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The mass of the link.
- Return type:
KinDynParameters
- Returns:
The updated kinematic and dynamic parameters of the model.
- support_body_array(link_index)[source]
Return the support parent array \(\kappa(i)\) of a link.
- Parameters:
link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.- Return type:
Array
- Returns:
The support parent array \(\kappa(i)\) of the link.
Note
This method returns a variable-length vector. In jit-compiled functions, it’s better to use the (static) boolean version support_body_array_bool.
- property support_body_array_bool: Array
Return the boolean support parent array \(\kappa_{b}(i)\) of the model.
- tree_transforms()[source]
Return the tree transforms of the model.
- Return type:
Array
- Returns:
The transforms \({}^{\text{pre}(i)} H_{\lambda(i)}\) of all joints of the model.
- class jaxsim.api.kin_dyn_parameters.LinkParameters(index, mass, center_of_mass, inertia_elements)[source]
Class storing the parameters of a link.
- Parameters:
index (Array)
mass (Array)
center_of_mass (Array)
inertia_elements (Array)
- index
The index of the link.
- mass
The mass of the link.
- inertia_elements
The unique elements of the \(3 \times 3\) inertia tensor of the link.
- center_of_mass
The translation \({}^L \mathbf{p}_{\text{CoM}}\) between the origin of the link frame and the link’s center of mass, expressed in the coordinates of the link frame.
Note
This class is used inside KinDynParameters to store the vectorized set of link parameters.
- static build_from_flat_parameters(index, parameters)[source]
Build a LinkParameters object from a flat vector of parameters.
- Parameters:
index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.parameters (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The flat vector of parameters.
- Return type:
LinkParameters
- Returns:
The LinkParameters object.
- static build_from_inertial_parameters(index, m, I, c)[source]
Build a LinkParameters object from the inertial parameters of a link.
- Parameters:
index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.m (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The mass of the link.I (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The \(3 \times 3\) inertia tensor of the link.c (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The translation between the link frame and the link’s center of mass.
- Return type:
LinkParameters
- Returns:
The LinkParameters object.
- static build_from_spatial_inertia(index, M)[source]
Build a LinkParameters object from a \(6 \times 6\) spatial inertia matrix.
- Parameters:
index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.M (
Array
) – The \(6 \times 6\) spatial inertia matrix of the link.
- Return type:
LinkParameters
- Returns:
The LinkParameters object.
- static flat_parameters(params)[source]
Return the parameters of a link as a flat vector.
- Parameters:
params (
LinkParameters
) – The link parameters.- Return type:
Array
- Returns:
The parameters of the link as a flat vector.
- static flatten_inertia_tensor(I)[source]
Flatten a \(3 \times 3\) inertia tensor into a vector of unique elements.
- Parameters:
I (
Array
) – The \(3 \times 3\) inertia tensor.- Return type:
Array
- Returns:
The vector of unique elements of the inertia tensor.
- static inertia_tensor(params)[source]
Return the \(3 \times 3\) inertia tensor of a link.
- Parameters:
params (
LinkParameters
) – The link parameters.- Return type:
Array
- Returns:
The \(3 \times 3\) inertia tensor of the link.
- static spatial_inertia(params)[source]
Return the \(6 \times 6\) spatial inertia matrix of a link.
- Parameters:
params (
LinkParameters
) – The link parameters.- Return type:
Array
- Returns:
The \(6 \times 6\) spatial inertia matrix of the link.
- static unflatten_inertia_tensor(inertia_elements)[source]
Unflatten a vector of unique elements into a \(3 \times 3\) inertia tensor.
- Parameters:
inertia_elements (
Array
) – The vector of unique elements of the inertia tensor.- Return type:
Array
- Returns:
The \(3 \times 3\) inertia tensor.
Joint#
- jaxsim.api.joint.idx_to_name(model, *, joint_index)[source]
Convert the index of a joint to its name.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the joint.
- Return type:
str
- Returns:
The name of the joint.
- jaxsim.api.joint.idxs_to_names(model, *, joint_indices)[source]
Convert a sequence of joint indices to their corresponding names.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_indices (
Union
[Sequence
[Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]],Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The indices of the joints.
- Return type:
tuple
[str
,...
]- Returns:
The names of the joints.
- jaxsim.api.joint.name_to_idx(model, *, joint_name)[source]
Convert the name of a joint to its index.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_name (
str
) – The name of the joint.
- Return type:
Array
- Returns:
The index of the joint.
- jaxsim.api.joint.names_to_idxs(model, *, joint_names)[source]
Convert a sequence of joint names to their corresponding indices.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_names (
Sequence
[str
]) – The names of the joints.
- Return type:
Array
- Returns:
The indices of the joints.
- jaxsim.api.joint.position_limit(model, *, joint_index)[source]
Get the position limits of a joint.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the joint.
- Return type:
tuple
[Array
,Array
]- Returns:
The position limits of the joint.
- jaxsim.api.joint.position_limits(model, *, joint_names=None)[source]
Get the position limits of a list of joint.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_names (
Sequence
[str
] |None
) – The names of the joints.
- Return type:
tuple
[Array
,Array
]- Returns:
The position limits of the joints.
- jaxsim.api.joint.random_joint_positions(model, *, joint_names=None, key=None)[source]
Generate random joint positions.
- Parameters:
model (
JaxSimModel
) – The model to consider.joint_names (
Sequence
[str
] |None
) – The names of the considered joints (all if None).key (
Array
|None
) – The random key (initialized from seed 0 if None).
- Return type:
Array
Note
If the joint range or revolute joints is larger than 2π, their joint positions will be sampled from an interval of size 2π.
- Return type:
Array
- Returns:
The random joint positions.
- Parameters:
model (JaxSimModel)
joint_names (Sequence[str] | None)
key (Array | None)
Link#
- jaxsim.api.link.bias_acceleration(model, data, *, link_index)[source]
Compute the bias acceleration of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.
- Return type:
Array
- Returns:
The 6D bias acceleration of the link.
- jaxsim.api.link.com_position(model, data, *, link_index, in_link_frame=True)[source]
Compute the position of the center of mass of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.in_link_frame (
Union
[bool
,Array
,ndarray
,bool
,number
,int
,float
,complex
]) – Whether to return the position in the link frame or in the world frame.
- Return type:
Array
- Returns:
The 3D position of the center of mass of the link.
- jaxsim.api.link.idx_to_name(model, *, link_index)[source]
Convert the index of a link to its name.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.
- Return type:
str
- Returns:
The name of the link.
- jaxsim.api.link.idxs_to_names(model, *, link_indices)[source]
Convert a sequence of link indices to their corresponding names.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_indices (
Union
[Sequence
[Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]],Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The indices of the links.
- Return type:
tuple
[str
,...
]- Returns:
The names of the links.
- jaxsim.api.link.jacobian(model, data, *, link_index, output_vel_repr=None)[source]
Compute the free-floating jacobian of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian.
- Return type:
Array
- Returns:
The \(6 \times (6+n)\) free-floating jacobian of the link.
Note
The input representation of the free-floating jacobian is the active velocity representation.
- jaxsim.api.link.jacobian_derivative(model, data, *, link_index, output_vel_repr=None)[source]
Compute the derivative of the free-floating jacobian of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian derivative.
- Return type:
Array
- Returns:
The derivative of the \(6 \times (6+n)\) free-floating jacobian of the link.
Note
The input representation of the free-floating jacobian derivative is the active velocity representation.
- jaxsim.api.link.mass(model, *, link_index)[source]
Return the mass of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.
- Return type:
Array
- Returns:
The mass of the link.
- jaxsim.api.link.name_to_idx(model, *, link_name)[source]
Convert the name of a link to its index.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_name (
str
) – The name of the link.
- Return type:
Array
- Returns:
The index of the link.
- jaxsim.api.link.names_to_idxs(model, *, link_names)[source]
Convert a sequence of link names to their corresponding indices.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_names (
Sequence
[str
]) – The names of the links.
- Return type:
Array
- Returns:
The indices of the links.
- jaxsim.api.link.spatial_inertia(model, *, link_index)[source]
Compute the 6D spatial inertial of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.
- Return type:
Array
- Returns:
The \(6 \times 6\) matrix representing the spatial inertia of the link expressed in the link frame (body-fixed representation).
- jaxsim.api.link.transform(model, data, *, link_index)[source]
Compute the SE(3) transform from the world frame to the link frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.
- Return type:
Array
- Returns:
The 4x4 matrix representing the transform.
- jaxsim.api.link.velocity(model, data, *, link_index, output_vel_repr=None)[source]
Compute the 6D velocity of the link.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the link.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the link velocity.
- Return type:
Array
- Returns:
The 6D velocity of the link in the specified velocity representation.
Frame#
- jaxsim.api.frame.idx_of_parent_link(model, *, frame_index)[source]
Get the index of the link to which the frame is rigidly attached.
- Parameters:
model (
JaxSimModel
) – The model to consider.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame.
- Return type:
Array
- Returns:
The index of the frame’s parent link.
- jaxsim.api.frame.idx_to_name(model, *, frame_index)[source]
Convert the index of a frame to its name.
- Parameters:
model (
JaxSimModel
) – The model to consider.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame.
- Return type:
str
- Returns:
The name of the frame.
- jaxsim.api.frame.idxs_to_names(model, *, frame_indices)[source]
Convert a sequence of frame indices to their corresponding names.
- Parameters:
model (
JaxSimModel
) – The model to consider.frame_indices (
Sequence
[Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]]) – The indices of the frames.
- Return type:
tuple
[str
,...
]- Returns:
The names of the frames.
- jaxsim.api.frame.jacobian(model, data, *, frame_index, output_vel_repr=None)[source]
Compute the free-floating jacobian of the frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian.
- Return type:
Array
- Returns:
The \(6 \times (6+n)\) free-floating jacobian of the frame.
Note
The input representation of the free-floating jacobian is the active velocity representation.
- jaxsim.api.frame.jacobian_derivative(model, data, *, frame_index, output_vel_repr=None)[source]
Compute the derivative of the free-floating jacobian of the frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the free-floating jacobian derivative.
- Return type:
Array
- Returns:
The derivative of the \(6 \times (6+n)\) free-floating jacobian of the frame.
Note
The input representation of the free-floating jacobian derivative is the active velocity representation.
- jaxsim.api.frame.name_to_idx(model, *, frame_name)[source]
Convert the name of a frame to its index.
- Parameters:
model (
JaxSimModel
) – The model to consider.frame_name (
str
) – The name of the frame.
- Return type:
Array
- Returns:
The index of the frame.
- jaxsim.api.frame.names_to_idxs(model, *, frame_names)[source]
Convert a sequence of frame names to their corresponding indices.
- Parameters:
model (
JaxSimModel
) – The model to consider.frame_names (
Sequence
[str
]) – The names of the frames.
- Return type:
Array
- Returns:
The indices of the frames.
- jaxsim.api.frame.transform(model, data, *, frame_index)[source]
Compute the SE(3) transform from the world frame to the specified frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame for which the transform is requested.
- Return type:
Array
- Returns:
The 4x4 matrix representing the transform.
- jaxsim.api.frame.velocity(model, data, *, frame_index, output_vel_repr=None)[source]
Compute the 6D velocity of the frame.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.frame_index (
Union
[int
,Array
,ndarray
,bool
,number
,bool
,float
,complex
]) – The index of the frame.output_vel_repr (
VelRepr
|None
) – The output velocity representation of the frame velocity.
- Return type:
Array
- Returns:
The 6D velocity of the frame in the specified velocity representation.
CoM#
- jaxsim.api.com.average_centroidal_velocity(model, data)[source]
Compute the average centroidal velocity of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The average centroidal velocity of the model.
Note
The average velocity is expressed in the mixed frame \(G = ({}^W \mathbf{p}_{\text{CoM}}, [C])\), where \([C] = [W]\) if the active velocity representation is either inertial-fixed or mixed, and \([C] = [B]\) if the active velocity representation is body-fixed.
- jaxsim.api.com.average_centroidal_velocity_jacobian(model, data)[source]
Compute the Jacobian of the average centroidal velocity of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The Jacobian of the average centroidal velocity of the model.
Note
The frame corresponding to the output representation of this Jacobian is either \(G[W]\), if the active velocity representation is inertial-fixed or mixed, or \(G[B]\), if the active velocity representation is body-fixed.
- jaxsim.api.com.bias_acceleration(model, data)[source]
Compute the bias linear acceleration of the center of mass.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The bias linear acceleration of the center of mass in the active representation.
Note
The bias acceleration is expressed in the mixed frame \(G = ({}^W \mathbf{p}_{\text{CoM}}, [C])\), where \([C] = [W]\) if the active velocity representation is either inertial-fixed or mixed, and \([C] = [B]\) if the active velocity representation is body-fixed.
- jaxsim.api.com.centroidal_momentum(model, data)[source]
Compute the centroidal momentum of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The centroidal momentum of the model.
Note
The centroidal momentum is expressed in the mixed frame \(({}^W \mathbf{p}_{\text{CoM}}, [C])\), where \(C = W\) if the active velocity representation is either inertial-fixed or mixed, and \(C = B\) if the active velocity representation is body-fixed.
- jaxsim.api.com.centroidal_momentum_jacobian(model, data)[source]
Compute the Jacobian of the centroidal momentum of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The Jacobian of the centroidal momentum of the model.
Note
The frame corresponding to the output representation of this Jacobian is either \(G[W]\), if the active velocity representation is inertial-fixed or mixed, or \(G[B]\), if the active velocity representation is body-fixed.
Note
This Jacobian is also known in the literature as Centroidal Momentum Matrix.
- jaxsim.api.com.com_linear_velocity(model, data)[source]
Compute the linear velocity of the center of mass of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The linear velocity of the center of mass of the model in the active representation.
Note
The linear velocity of the center of mass is expressed in the mixed frame \(G = ({}^W \mathbf{p}_{\text{CoM}}, [C])\), where \([C] = [W]\) if the active velocity representation is either inertial-fixed or mixed, and \([C] = [B]\) if the active velocity representation is body-fixed.
- jaxsim.api.com.com_position(model, data)[source]
Compute the position of the center of mass of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The position of the center of mass of the model w.r.t. the world frame.
- jaxsim.api.com.locked_centroidal_spatial_inertia(model, data)[source]
Compute the locked centroidal spatial inertia of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Returns:
The locked centroidal spatial inertia of the model.
Integration#
- jaxsim.api.integrators.rk4_integration(model, data, link_forces, joint_torques)[source]
Integrate the system state using the Runge-Kutta 4 method.
- Return type:
JaxSimModelData
- Parameters:
model (JaxSimModel)
data (JaxSimModelData)
link_forces (Array)
joint_torques (Array)
- jaxsim.api.integrators.semi_implicit_euler_integration(model, data, link_forces, joint_torques)[source]
Integrate the system state using the semi-implicit Euler method.
- Return type:
JaxSimModelData
- Parameters:
model (JaxSimModel)
data (JaxSimModelData)
link_forces (Array)
joint_torques (Array)
- jaxsim.api.ode.system_acceleration(model, data, *, link_forces=None, joint_torques=None)[source]
Compute the system acceleration in the active representation.
- 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
]) – The 6D forces to apply to the links expressed in the same velocity representation of data.joint_torques (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint torques applied to the joints.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the base 6D acceleration in the active representation and the joint accelerations.
- jaxsim.api.ode.system_dynamics(model, data, *, link_forces=None, joint_torques=None, baumgarte_quaternion_regularization=1.0)[source]
Compute the dynamics of the system.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.link_forces (
Array
|None
) – The 6D forces to apply to the links expressed in the frame corresponding to the velocity representation of data.joint_torques (
Array
|None
) – The joint torques acting on the joints.baumgarte_quaternion_regularization (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The Baumgarte regularization coefficient used to adjust the norm of the quaternion (only used in integrators not operating on the SO(3) manifold).
- Return type:
dict
[str
,Array
]- Returns:
A dictionary containing the derivatives of the base position, the base quaternion, the joint positions, the base linear velocity, the base angular velocity, and the joint velocities.
- jaxsim.api.ode.system_position_dynamics(data, baumgarte_quaternion_regularization=1.0)[source]
Compute the dynamics of the system position.
- Parameters:
data (
JaxSimModelData
) – The data of the considered model.baumgarte_quaternion_regularization (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The Baumgarte regularization coefficient for adjusting the quaternion norm.
- Return type:
tuple
[Array
,Array
,Array
]- Returns:
A tuple containing the derivative of the base position, the derivative of the base quaternion, and the derivative of the joint positions.
Note
In inertial-fixed representation, the linear component of the base velocity is not the derivative of the base position. In fact, the base velocity is defined as: \({} ^W v_{W, B} = \begin{bmatrix} {} ^W \dot{p}_B S({} ^W \omega_{W, B}) {} ^W p _B\\ {} ^W \omega_{W, B} \end{bmatrix}\). Where \(S(\cdot)\) is the skew-symmetric matrix operator.
References#
- class jaxsim.api.references.JaxSimModelReferences(_link_forces, _joint_force_references, *, velocity_representation=VelRepr.Inertial)[source]
Class containing the references for a JaxSimModel object.
- Parameters:
_link_forces (Array)
_joint_force_references (Array)
velocity_representation (Annotated[VelRepr, '__jax_dataclasses_static_field__'])
- _link_forces
The link 6D forces in inertial-fixed representation.
- _joint_force_references
The joint force references.
- apply_frame_forces(forces, model, data, frame_names=None, additive=False)[source]
Apply the frame forces.
- Parameters:
forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The frame 6D forces in the active representation.model (
JaxSimModel
) – The model to consider, only needed if a frame serialization different from the implicit one is used.data (
JaxSimModelData
) – The data of the considered model, only needed if the velocity representation is not inertial-fixed.frame_names (
tuple
[str
,...
] |str
|None
) – The names of the frames corresponding to the forces.additive (
bool
) – Whether to add the forces to the existing ones instead of replacing them.
- Return type:
Self
- Returns:
A new JaxSimModelReferences object with the given frame forces.
Note
The frame forces must be expressed in the active representation. Then, we always convert and store forces in inertial-fixed representation.
- apply_link_forces(forces, model=None, data=None, link_names=None, additive=False)[source]
Apply the link forces.
- Parameters:
forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The link 6D forces in the active representation.model (
JaxSimModel
|None
) – The model to consider, only needed if a link serialization different from the implicit one is used.data (
JaxSimModelData
|None
) – The data of the considered model, only needed if the velocity representation is not inertial-fixed.link_names (
tuple
[str
,...
] |str
|None
) – The names of the links corresponding to the forces.additive (
bool
) – Whether to add the forces to the existing ones instead of replacing them.
- Return type:
Self
- Returns:
A new JaxSimModelReferences object with the given link forces.
Note
The link forces must be expressed in the active representation. Then, we always convert and store forces in inertial-fixed representation.
- static build(model, joint_force_references=None, link_forces=None, data=None, velocity_representation=None)[source]
Create a JaxSimModelReferences object with the given references.
- Parameters:
model (
JaxSimModel
) – The model for which to create the state.joint_force_references (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint force references.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The link 6D forces in the desired representation.data (
JaxSimModelData
|None
) – The data of the model, only needed if the velocity representation is not inertial-fixed.velocity_representation (
VelRepr
|None
) – The velocity representation to use.
- Return type:
JaxSimModelReferences
- Returns:
A JaxSimModelReferences object with the given references.
- joint_force_references(model=None, joint_names=None)[source]
Return the joint force references.
- Parameters:
model (
JaxSimModel
|None
) – The model to consider.joint_names (
tuple
[str
,...
] |None
) – The names of the joints corresponding to the forces.
- Return type:
Array
- Returns:
If no model and no joint names are provided, the joint forces as a (DoFs,) vector corresponding to the default joint serialization of the original model used to build the actuation object. If a model is provided and no joint names are provided, the joint forces as a (DoFs,) vector corresponding to the serialization of the provided model. If both a model and joint names are provided, the joint forces as a (len(joint_names),) vector corresponding to the serialization of the passed joint names vector.
Note
The returned joint forces are those passed as user inputs when integrating the dynamics of the model. They are summed with other joint forces related e.g. to the enforcement of other kinematic constraints. Keep also in mind that the presence of joint friction and other similar effects can make the actual joint forces different from the references.
- link_forces(model=None, data=None, link_names=None)[source]
Return the link forces expressed in the frame of the active representation.
- Parameters:
model (
JaxSimModel
|None
) – The model to consider.data (
JaxSimModelData
|None
) – The data of the considered model.link_names (
tuple
[str
,...
] |None
) – The names of the links corresponding to the forces.
- Return type:
Array
- Returns:
If no model and no link names are provided, the link forces as a (n_links,6) matrix corresponding to the default link serialization of the original model used to build the actuation object. If a model is provided and no link names are provided, the link forces as a (n_links,6) matrix corresponding to the serialization of the provided model. If both a model and link names are provided, the link forces as a (len(link_names),6) matrix corresponding to the serialization of the passed link names vector.
Note
The returned link forces are those passed as user inputs when integrating the dynamics of the model. They are summed with other forces related e.g. to the contact model and other kinematic constraints.
- set_joint_force_references(forces, model=None, joint_names=None)[source]
Set the joint force references.
- Parameters:
forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The joint force references.model (
JaxSimModel
|None
) – The model to consider, only needed if a joint serialization different from the implicit one is used.joint_names (
tuple
[str
,...
] |None
) – The names of the joints corresponding to the forces.
- Return type:
Self
- Returns:
A new JaxSimModelReferences object with the given joint force references.
- valid(model=None)[source]
Check if the current references are valid for the given model.
- Parameters:
model (
JaxSimModel
|None
) – The model to check against.- Return type:
bool
- Returns:
True if the current references are valid for the given model, False otherwise.
- static zero(model, data=None, velocity_representation=VelRepr.Inertial)[source]
Create a JaxSimModelReferences object with zero references.
- Parameters:
model (
JaxSimModel
) – The model for which to create the zero references.data (
JaxSimModelData
|None
) – The data of the model, only needed if the velocity representation is not inertial-fixed.velocity_representation (
VelRepr
) – The velocity representation to use.
- Return type:
JaxSimModelReferences
- Returns:
A JaxSimModelReferences object with zero state.
Common#
- class jaxsim.api.common.VelRepr(*values)[source]#
Enumeration of all supported 6D velocity representations.
- class jaxsim.api.common.ModelDataWithVelocityRepresentation(*, velocity_representation=VelRepr.Inertial)[source]#
Base class for model data structures with velocity representation.
- Parameters:
velocity_representation (Annotated[VelRepr, '__jax_dataclasses_static_field__'])
- static inertial_to_other_representation(array, other_representation, transform, *, is_force)[source]#
Convert a 6D quantity from inertial-fixed to another representation.
- Parameters:
array (
Array
) – The 6D quantity to convert.other_representation (
VelRepr
) – The representation to convert to.transform (
Array
) – The \(W \mathbf{H}_O\) transform, where \(O\) is the reference frame of the other representation.is_force (
bool
) – Whether the quantity is a 6D force or a 6D velocity.
- Return type:
Array
- Returns:
The 6D quantity in the other representation.
- static other_representation_to_inertial(array, other_representation, transform, *, is_force)[source]#
Convert a 6D quantity from another representation to inertial-fixed.
- Parameters:
array (
Array
) – The 6D quantity to convert.other_representation (
VelRepr
) – The representation to convert from.transform (
Array
) – The math:W mathbf{H}_O transform, where math:O is the reference frame of the other representation.is_force (
bool
) – Whether the quantity is a 6D force or a 6D velocity.
- Return type:
Array
- Returns:
The 6D quantity in the inertial-fixed representation.
- switch_velocity_representation(velocity_representation)[source]#
Context manager to temporarily switch the velocity representation.
- Parameters:
velocity_representation (
VelRepr
) – The new velocity representation.- Yields:
The same object with the new velocity representation.
- Return type:
Iterator
[Self
]