Functional API#
Model#
- class jaxsim.api.model.JaxSimModel(model_name, terrain=FlatTerrain(_height=0.0), contact_model=None, kin_dyn_parameters=None, 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__'])
terrain (Annotated[Terrain, '__jax_dataclasses_static_field__'])
contact_model (ContactModel | None)
kin_dyn_parameters (KynDynParameters | None)
built_from (Annotated[str | Path | Model | None, '__jax_dataclasses_static_field__'])
_description (Annotated[HashlessObject[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.
- static build(model_description, model_name=None, *, terrain=None, contact_model=None)[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 optional name of the model overriding the physics model name.terrain (
Terrain
|None
) – The optional terrain to consider.contact_model (
ContactModel
|None
) – The optional contact model to consider. If None, the soft contact model is used.
- Return type:
JaxSimModel
- Returns:
The built Model object.
- static build_from_model_description(model_description, model_name=None, *, terrain=None, contact_model=None, is_urdf=None, considered_joints=None)[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 optional name of the model that overrides the one in the description.terrain (
Terrain
|None
) – The optional terrain to consider.is_urdf (
bool
|None
) – Whether the model description is a URDF or an SDF. This is automatically inferred if the model description is a path to a file.considered_joints (
Sequence
[str
] |None
) – The list of joints to consider. If None, all joints are considered.contact_model (ContactModel | None)
- Return type:
JaxSimModel
- Returns:
The built Model object.
- 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_joints()[source]
Return the number of joints in the model.
- Return type:
Array
- Returns:
The number of joints in the model.
- number_of_links()[source]
Return the number of links in the model.
- Return type:
Array
- 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 SE(3) transforms from the world frame to the frames of all links.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
A (nL, 4, 4) array containing the stacked SE(3) transforms 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_contact_forces(model, data)[source]
Compute the 6D contact forces of all links of the model.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
A (nL, 6) array containing the stacked 6D contact forces of the links, expressed in the frame corresponding to the active representation.
- 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
,Array
] |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, *, dt, integrator, integrator_state=None, joint_forces=None, link_forces=None, **kwargs)[source]
Perform a simulation step.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.dt (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The time step to consider.integrator (
Integrator
) – The integrator to use.integrator_state (
dict
[str
,Any
] |None
) – The state of the integrator.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint forces to consider.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The 6D forces to apply to the links expressed in the frame corresponding to the velocity representation of data.kwargs – Additional kwargs to pass to the integrator.
- Return type:
tuple
[JaxSimModelData
,dict
[str
,Any
]]- Returns:
A tuple containing the new data of the model and the new state of the integrator.
- 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.
Data#
- class jaxsim.api.data.JaxSimModelData(state, gravity, contacts_params, time_ns=<factory>, *, velocity_representation=VelRepr.Inertial)[source]
Class containing the data of a JaxSimModel object.
- Parameters:
state (ODEState)
gravity (Array)
contacts_params (ContactsParams)
time_ns (Array)
velocity_representation (Annotated[VelRepr, '__jax_dataclasses_static_field__'])
- base_orientation(dcm=False)[source]
Get the base orientation.
- Parameters:
dcm (
Union
[bool
,Array
,ndarray
,bool
,number
,int
,float
,complex
]) – Whether to return the orientation as a SO(3) matrix or quaternion.- Return type:
Array
- Returns:
The base orientation.
- base_position()[source]
Get the base position.
- Return type:
Array
- Returns:
The base position.
- base_transform()[source]
Get the base transform.
- Return type:
Array
- Returns:
The base transform as an SE(3) matrix.
- base_velocity()[source]
Get the base 6D velocity.
- Return type:
Array
- 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, standard_gravity=9.81, contact=None, contacts_params=None, velocity_representation=VelRepr.Inertial, time=None)[source]
Create a JaxSimModelData object with the given state.
- Parameters:
model (
JaxSimModel
) – The model for which to create the state.base_position (
Array
|None
) – The base position.base_quaternion (
Array
|None
) – The base orientation as a quaternion.joint_positions (
Array
|None
) – The joint positions.base_linear_velocity (
Array
|None
) – The base linear velocity in the selected representation.base_angular_velocity (
Array
|None
) – The base angular velocity in the selected representation.joint_velocities (
Array
|None
) – The joint velocities.standard_gravity (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The standard gravity constant.contact (
ContactsState
|None
) – The state of the soft contacts.contacts_params (
ContactsParams
|None
) – The parameters of the soft contacts.velocity_representation (
VelRepr
) – The velocity representation to use.time (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
,None
]) – The time at which the state is created.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData object with the given state.
- generalized_position()[source]
Get the generalized position \(\mathbf{q} = ({}^W \mathbf{H}_B, \mathbf{s}) \in \text{SO}(3) \times \mathbb{R}^n\).
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the base transform and the joint positions.
- generalized_velocity()[source]
Get the generalized velocity \(\boldsymbol{\nu} = (\boldsymbol{v}_{W,B};\, \boldsymbol{\omega}_{W,B};\, \mathbf{s}) \in \mathbb{R}^{6+n}\)
- Return type:
Array
- Returns:
The generalized velocity in the active representation.
- joint_positions(model=None, joint_names=None)[source]
Get the joint positions.
- Parameters:
model (
JaxSimModel
|None
) – The model to consider.joint_names (
tuple
[str
,...
] |None
) – The names of the joints for which to get the positions. If None, the positions of all joints are returned.
- Return type:
Array
- Returns:
If no model and no joint names are provided, the joint positions as a (DoFs,) vector corresponding to the serialization of the original model used to build the data object. If a model is provided and no joint names are provided, the joint positions as a (DoFs,) vector corresponding to the serialization of the provided model. If a model and joint names are provided, the joint positions as a (len(joint_names),) vector corresponding to the serialization of the passed joint names vector.
- joint_velocities(model=None, joint_names=None)[source]
Get the joint velocities.
- Parameters:
model (
JaxSimModel
|None
) – The model to consider.joint_names (
tuple
[str
,...
] |None
) – The names of the joints for which to get the velocities. If None, the velocities of all joints are returned.
- Return type:
Array
- Returns:
If no model and no joint names are provided, the joint velocities as a (DoFs,) vector corresponding to the serialization of the original model used to build the data object. If a model is provided and no joint names are provided, the joint velocities as a (DoFs,) vector corresponding to the serialization of the provided model. If a model and joint names are provided, the joint velocities as a (len(joint_names),) vector corresponding to the serialization of the passed joint names vector.
- reset_base_angular_velocity(angular_velocity, velocity_representation=None)[source]
Reset the base angular velocity.
- Parameters:
angular_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base angular velocity as a 3D array.velocity_representation (
VelRepr
|None
) – The velocity representation in which the base velocity is expressed. If None, the active representation is considered.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_base_linear_velocity(linear_velocity, velocity_representation=None)[source]
Reset the base linear velocity.
- Parameters:
linear_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base linear velocity as a 3D array.velocity_representation (
VelRepr
|None
) – The velocity representation in which the base velocity is expressed. If None, the active representation is considered.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_base_pose(base_pose)[source]
Reset the base pose.
- Parameters:
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_position(base_position)[source]
Reset the base position.
- Parameters:
base_position (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base position.- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_base_quaternion(base_quaternion)[source]
Reset the base quaternion.
- Parameters:
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.
- reset_base_velocity(base_velocity, velocity_representation=None)[source]
Reset the base 6D velocity.
- Parameters:
base_velocity (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The base 6D velocity in the active representation.velocity_representation (
VelRepr
|None
) – The velocity representation in which the base velocity is expressed. If None, the active representation is considered.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_joint_positions(positions, model=None, joint_names=None)[source]
Reset the joint positions.
- Parameters:
positions (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The joint positions.model (
JaxSimModel
|None
) – The model to consider.joint_names (
tuple
[str
,...
] |None
) – The names of the joints for which to set the positions.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- reset_joint_velocities(velocities, model=None, joint_names=None)[source]
Reset the joint velocities.
- Parameters:
velocities (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The joint velocities.model (
JaxSimModel
|None
) – The model to consider.joint_names (
tuple
[str
,...
] |None
) – The names of the joints for which to set the velocities.
- Return type:
Self
- Returns:
The updated JaxSimModelData object.
- standard_gravity()[source]
Get the standard gravity constant.
- Return type:
Array
- Returns:
The standard gravity constant.
- time()[source]
Get the simulated time.
- Return type:
Array
- Returns:
The simulated time in seconds.
- valid(model=None)[source]
Check if the current state is valid for the given model.
- Parameters:
model (
JaxSimModel
|None
) – The model to check against.- Return type:
bool
- Returns:
True if the current state is valid for the given model, False otherwise.
- static zero(model, velocity_representation=VelRepr.Inertial)[source]
Create a JaxSimModelData object with zero state.
- Parameters:
model (
JaxSimModel
) – The model for which to create the zero state.velocity_representation (
VelRepr
) – The velocity representation to use.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData object 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), standard_gravity_bounds=(9.81, 9.81))[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.standard_gravity_bounds (
tuple
[Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
],Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]]) – The bounds for the standard gravity.
- Return type:
JaxSimModelData
- Returns:
A JaxSimModelData object with random data.
Contact#
- jaxsim.api.contact.collidable_point_dynamics(model, data, link_forces=None, joint_force_references=None)[source]
Compute the 6D force applied to each collidable point.
- 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 the same representation of data.joint_force_references (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint force references to apply to the joints.
- Returns:
Soft: the material deformation rate.
Rigid: no additional data.
QuasiRigid: no additional data.
- Return type:
The 6D force applied to each collidable point and additional data based on the contact model configured
Note
The material deformation rate is always returned in the mixed frame C[W] = ({}^W mathbf{p}_C, [W]). This is convenient for integration purpose. Instead, the 6D forces are returned in the active representation.
- jaxsim.api.contact.collidable_point_forces(model, data)[source]
Compute the 6D forces applied to each collidable point.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.
- Return type:
Array
- Returns:
The 6D forces applied to each collidable point expressed in the frame corresponding to the active representation.
- 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_soft_contacts_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 soft contacts parameters for the given model.
- Parameters:
model (
JaxSimModel
) – The model to consider.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.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 supporting the weight of the robot.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 in steady state when the robot is supported by the configured number of active collidable points.
- Return type:
SoftContactsParams
- Returns:
The estimated good soft contacts parameters.
Note
This method provides a good starting point for the soft contacts parameters. The user is encouraged to fine-tune the parameters based on the specific application.
- 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 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 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 contact 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 contact points.
Note
The input representation of the free-floating jacobian derivative is the active velocity representation.
- jaxsim.api.contact.transforms(model, data)[source]
Return the pose of the 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 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>)[source]
Class storing the contact parameters of a model.
- Parameters:
body (Annotated[tuple[int, ...], '__jax_dataclasses_static_field__'])
point (Array)
- 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.
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.
- 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 (Array)
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.KynDynParameters(link_names, _parent_array, _support_body_array_bool, 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[HashedNumpyArray, '__jax_dataclasses_static_field__'])
_support_body_array_bool (Annotated[HashedNumpyArray, '__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:
KynDynParameters
- 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_motion_subspaces(joint_positions, base_transform)[source]
Return the motion subspaces 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 motion subspaces \(\mathbf{S}(s)\) of each joint.
- 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.
- joint_transforms_and_motion_subspaces(joint_positions, base_transform)[source]
Return the transforms and the motion subspaces 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:
tuple
[Array
,Array
]- Returns:
A tuple containing the stacked transforms \({}^{i} \mathbf{H}_{\lambda(i)}(s)\) and the stacked motion subspaces \(\mathbf{S}(s)\) of each joint.
Note
The first transform, at index 0, provides the pose of the base link w.r.t. the world frame. For both floating-base and fixed-base systems, it takes into account the base pose and the optional transform between the root frame of the model and the base link.
- 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.
- 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.
- set_link_inertia(link_index, inertia)[source]
Set the inertia tensor of a link.
- Parameters:
link_index (
int
) – 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:
KynDynParameters
- 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 (
int
) – The index of the link.mass (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The mass of the link.
- Return type:
KynDynParameters
- 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.
- 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_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.
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.
ODE Data#
- class jaxsim.api.ode_data.ODEInput(physics_model)[source]
The input to the ODE system.
- Parameters:
physics_model (PhysicsModelInput)
- physics_model
The input to the physics model.
- static build(physics_model_input=None, model=None)[source]
Build an ODEInput from a PhysicsModelInput.
- Parameters:
physics_model_input (
PhysicsModelInput
|None
) – The PhysicsModelInput associated with the ODE input.model (
JaxSimModel
|None
) – The JaxSimModel associated with the ODE input.
- Return type:
ODEInput
- Returns:
A ODEInput instance.
- static build_from_jaxsim_model(model=None, joint_forces=None, link_forces=None)[source]
Build an ODEInput from a JaxSimModel.
- Parameters:
model (
JaxSimModel
|None
) – The JaxSimModel associated with the ODE input.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The vector of joint forces.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The matrix of external forces applied to the links.
- Return type:
ODEInput
- Returns:
The ODEInput built from the JaxSimModel.
Note
If any of the input components are not provided, they are built from the JaxSimModel and initialized to zero.
- valid(model)[source]
Check if the ODEInput is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the ODEInput against.- Return type:
bool
- Returns:
True if the ODE input is valid for the given model, False otherwise.
- static zero(model)[source]
Build a zero ODEInput from a JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel associated with the ODE input.- Return type:
ODEInput
- Returns:
A zero ODEInput instance.
- class jaxsim.api.ode_data.ODEState(physics_model, contact)[source]
The state of the ODE system.
- Parameters:
physics_model (PhysicsModelState)
contact (ContactsState)
- physics_model
The state of the physics model.
- contact
The state of the contacts model.
- static build(physics_model_state=None, contact=None, model=None)[source]
Build an ODEState from a PhysicsModelState and a ContactsState.
- Parameters:
physics_model_state (
PhysicsModelState
|None
) – The state of the physics model.contact (
ContactsState
|None
) – The state of the contacts model.model (
JaxSimModel
|None
) – The JaxSimModel associated with the ODE state.
- Return type:
ODEState
- Returns:
A ODEState instance.
- static build_from_jaxsim_model(model=None, joint_positions=None, joint_velocities=None, base_position=None, base_quaternion=None, base_linear_velocity=None, base_angular_velocity=None, **kwargs)[source]
Build an ODEState from a JaxSimModel.
- Parameters:
model (
JaxSimModel
|None
) – The JaxSimModel associated with the ODE state.joint_positions (
Array
|None
) – The vector of joint positions.joint_velocities (
Array
|None
) – The vector of joint velocities.base_position (
Array
|None
) – The 3D position of the base link.base_quaternion (
Array
|None
) – The quaternion defining the orientation of the base link.base_linear_velocity (
Array
|None
) – The linear velocity of the base link in inertial-fixed representation.base_angular_velocity (
Array
|None
) – The angular velocity of the base link in inertial-fixed representation.kwargs – Additional arguments needed to build the contact state.
- Return type:
ODEState
- Returns:
The ODEState 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 ODEState is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the ODEState against.- Return type:
bool
- Returns:
True if the ODE state is valid for the given model, False otherwise.
- static zero(model, data)[source]
Build a zero ODEState from a JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel associated with the ODE state.data (JaxSimModelData)
- Return type:
ODEState
- Returns:
A zero ODEState instance.
- class jaxsim.api.ode_data.PhysicsModelInput(tau, f_ext)[source]
Class storing the inputs of the physics model dynamics.
- Parameters:
tau (Array)
f_ext (Array)
- tau
The vector of joint forces.
- f_ext
The matrix of external forces applied to the links.
- static build(joint_forces=None, link_forces=None, number_of_dofs=None, number_of_links=None)[source]
Build a PhysicsModelInput.
- Parameters:
joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The vector of joint forces.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The matrix of external forces applied to the links.number_of_dofs (
Array
|None
) – The number of degrees of freedom of the model.number_of_links (
Array
|None
) – The number of links of the model.
- Return type:
PhysicsModelInput
- Returns:
A PhysicsModelInput instance.
- static build_from_jaxsim_model(model=None, joint_forces=None, link_forces=None)[source]
Build a PhysicsModelInput from a JaxSimModel.
- Parameters:
model (
JaxSimModel
|None
) – The JaxSimModel associated with the input.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The vector of joint forces.link_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The matrix of external forces applied to the links.
- Return type:
PhysicsModelInput
- Returns:
A PhysicsModelInput instance.
Note
If any of the input components are not provided, they are built from the JaxSimModel and initialized to zero.
- valid(model)[source]
Check if the PhysicsModelInput is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the PhysicsModelInput against.- Return type:
bool
- Returns:
True if the PhysicsModelInput is valid for the given model, False otherwise.
- static zero(model)[source]
Build a PhysicsModelInput with all components initialized to zero.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel associated with the input.- Return type:
PhysicsModelInput
- Returns:
A PhysicsModelInput instance.
- class jaxsim.api.ode_data.PhysicsModelState(joint_positions, joint_velocities, base_position=<factory>, base_quaternion=<factory>, base_linear_velocity=<factory>, base_angular_velocity=<factory>)[source]
Class storing the state of the physics model dynamics.
- Parameters:
joint_positions (Array)
joint_velocities (Array)
base_position (Array)
base_quaternion (Array)
base_linear_velocity (Array)
base_angular_velocity (Array)
- 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.
- static build(joint_positions=None, joint_velocities=None, base_position=None, base_quaternion=None, base_linear_velocity=None, base_angular_velocity=None, number_of_dofs=None)[source]
Build a PhysicsModelState.
- Parameters:
joint_positions (
Array
|None
) – The vector of joint positions.joint_velocities (
Array
|None
) – The vector of joint velocities.base_position (
Array
|None
) – The 3D position of the base link.base_quaternion (
Array
|None
) – The quaternion defining the orientation of the base link.base_linear_velocity (
Array
|None
) – The linear velocity of the base link in inertial-fixed representation.base_angular_velocity (
Array
|None
) – The angular velocity of the base link in inertial-fixed representation.number_of_dofs (
Array
|None
) – The number of degrees of freedom of the physics model.
- Return type:
PhysicsModelState
- Returns:
A PhysicsModelState instance.
- static build_from_jaxsim_model(model=None, joint_positions=None, joint_velocities=None, base_position=None, base_quaternion=None, base_linear_velocity=None, base_angular_velocity=None)[source]
Build a PhysicsModelState from a JaxSimModel.
- Parameters:
model (
JaxSimModel
|None
) – The JaxSimModel associated with the state.joint_positions (
Array
|None
) – The vector of joint positions.joint_velocities (
Array
|None
) – The vector of joint velocities.base_position (
Array
|None
) – The 3D position of the base link.base_quaternion (
Array
|None
) – The quaternion defining the orientation of the base link.base_linear_velocity (
Array
|None
) – The linear velocity of the base link in inertial-fixed representation.base_angular_velocity (
Array
|None
) – The angular velocity of the base link in inertial-fixed representation.
- Return type:
PhysicsModelState
Note
If any of the state components are not provided, they are built from the JaxSimModel and initialized to zero.
- Return type:
PhysicsModelState
- Returns:
A PhysicsModelState instance.
- Parameters:
model (JaxSimModel | None)
joint_positions (Array | None)
joint_velocities (Array | None)
base_position (Array | None)
base_quaternion (Array | None)
base_linear_velocity (Array | None)
base_angular_velocity (Array | None)
- valid(model)[source]
Check if the PhysicsModelState is valid for a given JaxSimModel.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel to validate the PhysicsModelState against.- Return type:
bool
- Returns:
True if the PhysicsModelState is valid for the given model, False otherwise.
- static zero(model)[source]
Build a PhysicsModelState with all components initialized to zero.
- Parameters:
model (
JaxSimModel
) – The JaxSimModel associated with the state.- Return type:
PhysicsModelState
- Returns:
A PhysicsModelState instance.
- class jaxsim.api.ode.SystemDynamicsFromModelAndData(*args, **kwargs)[source]
- jaxsim.api.ode.system_acceleration(model, data, *, joint_forces=None, link_forces=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.joint_forces (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
,None
]) – The joint forces to apply.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 representation of data.
- Return type:
tuple
[Array
,Array
]- Returns:
A tuple containing the base 6D acceleration in in the active representation and the joint accelerations.
- jaxsim.api.ode.system_dynamics(model, data, *, joint_forces=None, link_forces=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.joint_forces (
Array
|None
) – The joint forces to apply.link_forces (
Array
|None
) – The 6D forces to apply to the links expressed in the frame corresponding to the velocity representation of data.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:
tuple
[ODEState
,dict
[str
,Any
]]- Returns:
A tuple with an ODEState object storing in each of its attributes the corresponding derivative, and the dictionary of auxiliary data returned by the system dynamics evaluation.
- jaxsim.api.ode.system_position_dynamics(model, data, baumgarte_quaternion_regularization=1.0)[source]
Compute the dynamics of the system position.
- Parameters:
model (
JaxSimModel
) – The model to consider.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.
- jaxsim.api.ode.system_velocity_dynamics(model, data, *, joint_forces=None, link_forces=None)[source]
Compute the dynamics of the system velocity.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.joint_forces (
Array
|None
) – The joint force references to apply.link_forces (
Array
|None
) – The 6D forces to apply to the links expressed in the frame corresponding to the velocity representation of data.
- Return type:
tuple
[Array
,Array
,dict
[str
,Any
]]- Returns:
A tuple containing the derivative of the base 6D velocity in inertial-fixed representation, the derivative of the joint velocities, and auxiliary data returned by the system dynamics evaluation.
- jaxsim.api.ode.wrap_system_dynamics_for_integration(model, data, *, system_dynamics, **kwargs)[source]
Wrap generic system dynamics operating on JaxSimModel and JaxSimModelData for integration with jaxsim.integrators.
- Parameters:
model (
JaxSimModel
) – The model to consider.data (
JaxSimModelData
) – The data of the considered model.system_dynamics (
SystemDynamicsFromModelAndData
) – The system dynamics to wrap.**kwargs – Additional kwargs to close over the system dynamics.
- Return type:
SystemDynamics
[ODEState
,ODEState
]- Returns:
The system dynamics closed over the model, the data, and the additional kwargs.
References#
- class jaxsim.api.references.JaxSimModelReferences(input, *, velocity_representation=VelRepr.Inertial)[source]
Class containing the references for a JaxSimModel object.
- Parameters:
input (ODEInput)
velocity_representation (Annotated[VelRepr, '__jax_dataclasses_static_field__'])
- 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 (
Array
|None
) – The joint force references.link_forces (
Array
|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#
- flag jaxsim.api.common.VelRepr(value)[source]#
Enumeration of all supported 6D velocity representations.
- Member Type:
int
Valid values are as follows:
- Body = <VelRepr.Body: 1>#
- Mixed = <VelRepr.Mixed: 2>#
- Inertial = <VelRepr.Inertial: 3>#
- 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
]