jaxtransform3d.transformations.transform_from_exponential_coordinates#

jaxtransform3d.transformations.transform_from_exponential_coordinates(exp_coords: Array | ndarray | bool_ | number | bool | int | float | complex) Array[source]#

Compute transformation matrix from exponential coordinates.

This is the exponential map.

\[Exp: \mathcal{S} \theta \in \mathbb{R}^6 \rightarrow \boldsymbol{T} \in SE(3)\]
\[\begin{split}Exp(\mathcal{S}\theta) = Exp\left(\left(\begin{array}{c} \hat{\boldsymbol{\omega}}\\ \boldsymbol{v} \end{array}\right)\theta\right) = \exp(\left[\mathcal{S}\right] \theta) = \left(\begin{array}{cc} Exp(\hat{\boldsymbol{\omega}} \theta) & \boldsymbol{J}(\theta)\boldsymbol{v}\theta\\ \boldsymbol{0} & 1 \end{array}\right),\end{split}\]

where \(\boldsymbol{J}(\theta)\) is the left Jacobian of \(SO(3)\).

Parameters:
exp_coordsarray-like, shape (…, 6)

Exponential coordinates of transformation: S * theta = (omega_1, omega_2, omega_3, v_1, v_2, v_3) * theta, where S is the screw axis, the first 3 components are related to rotation and the last 3 components are related to translation. Theta is the rotation angle and h * theta the translation.

Returns:
Tarray, shape (…, 4, 4)

Transformation matrix.

See also

exponential_coordinates_from_transform

Logarithmic map.

dual_quaternion_from_exponential_coordinates

Exponential map for dual quaternions.