Math#

class jaxsim.math.adjoint.Adjoint[source]#

A utility class for adjoint matrix operations.

static from_quaternion_and_translation(quaternion=None, translation=None, inverse=False, normalize_quaternion=False)[source]#

Create an adjoint matrix from a quaternion and a translation.

Parameters:
  • quaternion (Array | None) – A quaternion vector (4D) representing orientation.

  • translation (Array | None) – A translation vector (3D).

  • inverse (bool) – Whether to compute the inverse adjoint.

  • normalize_quaternion (bool) – Whether to normalize the quaternion before creating the adjoint.

Return type:

Array

Returns:

The adjoint matrix.

static from_rotation_and_translation(rotation=None, translation=None, inverse=False)[source]#

Create an adjoint matrix from a rotation matrix and a translation vector.

Parameters:
  • rotation (Array | None) – A 3x3 rotation matrix.

  • translation (Array | None) – A translation vector (3D).

  • inverse (bool) – Whether to compute the inverse adjoint. Default is False.

Return type:

Array

Returns:

The adjoint 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.

static inverse(adjoint)[source]#

Compute the inverse of an adjoint matrix.

Parameters:

adjoint (Array) – The adjoint matrix.

Return type:

Array

Returns:

The inverse adjoint matrix.

static to_transform(adjoint)[source]#

Convert an adjoint matrix to a transformation matrix.

Parameters:

adjoint (Array) – The adjoint matrix (6x6).

Return type:

Array

Returns:

The transformation matrix (4x4).

class jaxsim.math.cross.Cross[source]#

A utility class for cross product matrix operations.

static vx(velocity_sixd)[source]#

Compute the cross product matrix for 6D velocities.

Parameters:

velocity_sixd (Array) – A 6D velocity vector [v, ω].

Return type:

Array

Returns:

The cross product matrix (6x6).

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 (Array) – A 6D velocity vector [v, ω].

Return type:

Array

Returns:

The negative transpose of the cross product matrix (6x6).

Raises:

ValueError – If the input vector does not have a size of 6.

class jaxsim.math.inertia.Inertia[source]#

A utility class for inertia matrix operations.

static to_params(M)[source]#

Convert a 6x6 inertia matrix to mass, center of mass, and inertia matrix.

Parameters:

M (Array) – The 6x6 inertia matrix.

Return type:

tuple[Array, Array, Array]

Returns:

A tuple containing mass, center of mass (3D), and inertia matrix (3x3).

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 (Array) – The mass of the body.

  • com (Array) – The center of mass position (3D).

  • I (Array) – The 3x3 inertia matrix.

Return type:

Array

Returns:

The 6x6 inertia matrix.

Raises:

ValueError – If the shape of the inertia matrix I is not (3, 3).

class jaxsim.math.quaternion.Quaternion[source]#

A utility class for quaternion operations.

static derivative(quaternion, omega, omega_in_body_fixed=False, K=0.1)[source]#

Compute the derivative of a quaternion given angular velocity.

Parameters:
  • quaternion (Array) – Quaternion in XYZW representation.

  • omega (Array) – Angular velocity vector.

  • omega_in_body_fixed (bool) – Whether the angular velocity is in the body-fixed frame.

  • K (float) – A scaling factor.

Return type:

Array

Returns:

The derivative of the quaternion.

static from_dcm(dcm)[source]#

Convert a direction cosine matrix (DCM) to a quaternion.

Parameters:

dcm (Array) – Direction cosine matrix (DCM).

Return type:

Array

Returns:

Quaternion in WXYZ representation.

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 (Array) – Quaternion in XYZW representation.

Return type:

Array

Returns:

The Direction cosine matrix (DCM).

static to_wxyz(xyzw)[source]#

Convert a quaternion from XYZW to WXYZ representation.

Parameters:

xyzw (Array) – Quaternion in XYZW representation.

Return type:

Array

Returns:

Quaternion in WXYZ representation.

static to_xyzw(wxyz)[source]#

Convert a quaternion from WXYZ to XYZW representation.

Parameters:

wxyz (Array) – Quaternion in WXYZ representation.

Return type:

Array

Returns:

Quaternion in XYZW representation.

class jaxsim.math.rotation.Rotation[source]#

A utility class for rotation matrix operations.

static from_axis_angle(vector)[source]#

Generate a 3D rotation matrix from an axis-angle representation.

Parameters:

vector (Array) – Axis-angle representation or the rotation as a 3D vector.

Return type:

Array

Returns:

The SO(3) rotation matrix.

static x(theta)[source]#

Generate a 3D rotation matrix around the X-axis.

Parameters:

theta (Array) – Rotation angle in radians.

Return type:

Array

Returns:

The 3D rotation matrix.

static y(theta)[source]#

Generate a 3D rotation matrix around the Y-axis.

Parameters:

theta (Array) – Rotation angle in radians.

Return type:

Array

Returns:

The 3D rotation matrix.

static z(theta)[source]#

Generate a 3D rotation matrix around the Z-axis.

Parameters:

theta (Array) – Rotation angle in radians.

Return type:

Array

Returns:

The 3D rotation matrix.

class jaxsim.math.skew.Skew[source]#

A utility class for skew-symmetric matrix operations.

static vee(matrix)[source]#

Extract the 3D vector from a skew-symmetric matrix (vee operator).

Parameters:

matrix (Array) – A 3x3 skew-symmetric matrix.

Return type:

Array

Returns:

The 3D vector extracted from the input matrix.

static wedge(vector)[source]#

Compute the skew-symmetric matrix (wedge operator) of a 3D vector.

Parameters:

vector (Array) – A 3D vector.

Return type:

Array

Returns:

The skew-symmetric matrix corresponding to the input vector.