pytransform3d.transformations
.transform_log_from_exponential_coordinates#
- pytransform3d.transformations.transform_log_from_exponential_coordinates(Stheta)[source]#
Compute matrix logarithm of transformation from exponential coordinates.
Builds the matrix
\[\begin{split}\left( \begin{array}{cccc} 0 & -\omega_3 & \omega_2 & v_1\\ \omega_3 & 0 & -\omega_1 & v_2\\ -\omega_2 & \omega_1 & 0 & v_3\\ 0 & 0 & 0 & 0 \end{array} \right) \theta = \left[ \mathcal{S} \right] \theta \in so(3)\end{split}\]from the vector \(\mathcal{S} \theta = (\hat{\boldsymbol{\omega}}, \boldsymbol{v}) \theta \in \mathbb{R}^6\).
- Parameters:
- Sthetaarray-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:
- transform_logarray, shape (4, 4)
Matrix logarithm of transformation matrix: [S] * theta.