Math#
- class jaxsim.math.adjoint.Adjoint[source]#
- static from_quaternion_and_translation(quaternion=Array([1., 0., 0., 0.], dtype=float64), translation=Array([0., 0., 0.], dtype=float64), inverse=False, normalize_quaternion=False)[source]#
Create an adjoint matrix from a quaternion and a translation.
- Parameters:
quaternion (jtp.Vector) – A quaternion vector (4D) representing orientation.
translation (jtp.Vector) – A translation vector (3D).
inverse (bool) – Whether to compute the inverse adjoint. Default is False.
normalize_quaternion (bool) – Whether to normalize the quaternion before creating the adjoint. Default is False.
- Returns:
The adjoint matrix.
- Return type:
jtp.Matrix
- static from_rotation_and_translation(rotation=Array([[1., 0., 0.], [0., 1., 0.], [0., 0., 1.]], dtype=float64), translation=Array([0., 0., 0.], dtype=float64), inverse=False)[source]#
Create an adjoint matrix from a rotation matrix and a translation vector.
- Parameters:
rotation (jtp.Matrix) – A 3x3 rotation matrix.
translation (jtp.Vector) – A translation vector (3D).
inverse (bool) – Whether to compute the inverse adjoint. Default is False.
- Returns:
The adjoint matrix.
- Return type:
jtp.Matrix
- static from_transform(transform, inverse=False)[source]#
Create an adjoint matrix from a transformation matrix.
- Parameters:
transform (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – A 4x4 transformation matrix.inverse (
bool
) – Whether to compute the inverse adjoint.
- Return type:
Array
- Returns:
The 6x6 adjoint matrix.
- class jaxsim.math.cross.Cross[source]#
- static vx(velocity_sixd)[source]#
Compute the cross product matrix for 6D velocities.
- Parameters:
velocity_sixd (jtp.Vector) – A 6D velocity vector [v, ω].
- Returns:
The cross product matrix (6x6).
- Return type:
jtp.Matrix
- Raises:
ValueError – If the input vector does not have a size of 6.
- static vx_star(velocity_sixd)[source]#
Compute the negative transpose of the cross product matrix for 6D velocities.
- Parameters:
velocity_sixd (jtp.Vector) – A 6D velocity vector [v, ω].
- Returns:
The negative transpose of the cross product matrix (6x6).
- Return type:
jtp.Matrix
- Raises:
ValueError – If the input vector does not have a size of 6.
- class jaxsim.math.inertia.Inertia[source]#
- static to_params(M)[source]#
Convert a 6x6 inertia matrix to mass, center of mass, and inertia matrix.
- Parameters:
M (jtp.Matrix) – The 6x6 inertia matrix.
- Returns:
A tuple containing mass, center of mass (3D), and inertia matrix (3x3).
- Return type:
tuple[jtp.Float, jtp.Vector, jtp.Matrix]
- Raises:
ValueError – If the input matrix M has an unexpected shape.
- static to_sixd(mass, com, I)[source]#
Convert mass, center of mass, and inertia matrix to a 6x6 inertia matrix.
- Parameters:
mass (jtp.Float) – The mass of the body.
com (jtp.Vector) – The center of mass position (3D).
I (jtp.Matrix) – The 3x3 inertia matrix.
- Returns:
The 6x6 inertia matrix.
- Return type:
jtp.Matrix
- Raises:
ValueError – If the shape of the inertia matrix I is not (3, 3).
- class jaxsim.math.quaternion.Quaternion[source]#
- static derivative(quaternion, omega, omega_in_body_fixed=False, K=0.1)[source]#
Compute the derivative of a quaternion given angular velocity.
- Parameters:
quaternion (jtp.Vector) – Quaternion in XYZW representation.
omega (jtp.Vector) – Angular velocity vector.
omega_in_body_fixed (bool) – Whether the angular velocity is in the body-fixed frame.
K (float) – A scaling factor.
- Returns:
The derivative of the quaternion.
- Return type:
jtp.Vector
- static from_dcm(dcm)[source]#
Convert a direction cosine matrix (DCM) to a quaternion.
- Parameters:
dcm (jtp.Matrix) – Direction cosine matrix (DCM).
- Returns:
Quaternion in XYZW representation.
- Return type:
jtp.Vector
- static integration(quaternion, dt, omega, omega_in_body_fixed=False)[source]#
Integrate a quaternion in SO(3) given an angular velocity.
- Parameters:
quaternion (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The quaternion to integrate.dt (
Union
[float
,Array
,ndarray
,bool
,number
,bool
,int
,complex
]) – The time step.omega (
Union
[Array
,ndarray
,bool
,number
,bool
,int
,float
,complex
,tuple
]) – The angular velocity vector.omega_in_body_fixed (
Union
[bool
,Array
,ndarray
,bool
,number
,int
,float
,complex
]) – Whether the angular velocity is in body-fixed representation as opposed to the default inertial-fixed representation.
- Return type:
Array
- Returns:
The integrated quaternion.
- static to_dcm(quaternion)[source]#
Convert a quaternion to a direction cosine matrix (DCM).
- Parameters:
quaternion (jtp.Vector) – Quaternion in XYZW representation.
- Returns:
Direction cosine matrix (DCM).
- Return type:
jtp.Matrix
- class jaxsim.math.rotation.Rotation[source]#
- static from_axis_angle(vector)[source]#
Generate a 3D rotation matrix from an axis-angle representation.
- Parameters:
vector (jtp.Vector) – Axis-angle representation as a 3D vector.
- Returns:
3D rotation matrix.
- Return type:
jtp.Matrix
- static x(theta)[source]#
Generate a 3D rotation matrix around the X-axis.
- Parameters:
theta (jtp.Float) – Rotation angle in radians.
- Returns:
3D rotation matrix.
- Return type:
jtp.Matrix
- class jaxsim.math.skew.Skew[source]#
A utility class for skew-symmetric matrix operations.