pytransform3d.transformations.exponential_coordinates_from_transform

pytransform3d.transformations.exponential_coordinates_from_transform(A2B, strict_check=True, check=True)[source]

Compute exponential coordinates from transformation matrix.

Logarithmic map.

Log: \boldsymbol{T} \in SE(3)
\rightarrow \mathcal{S} \theta \in \mathbb{R}^6

Log(\boldsymbol{T}) =
Log\left(
\begin{array}{cc}
\boldsymbol{R} & \boldsymbol{p}\\
\boldsymbol{0} & 1
\end{array}
\right)
=
\left(
\begin{array}{c}
Log(\boldsymbol{R})\\
\boldsymbol{J}^{-1}(\theta) \boldsymbol{p}
\end{array}
\right)
=
\left(
\begin{array}{c}
\hat{\boldsymbol{\omega}}\\
\boldsymbol{v}
\end{array}
\right)
\theta
=
\mathcal{S}\theta,

where \boldsymbol{J}^{-1}(\theta) is the inverse left Jacobian of SO(3) (see left_jacobian_SO3_inv()).

Parameters:
A2Barray-like, shape (4, 4)

Transformation matrix from frame A to frame B

strict_checkbool, optional (default: True)

Raise a ValueError if the transformation matrix is not numerically close enough to a real transformation matrix. Otherwise we print a warning.

checkbool, optional (default: True)

Check if transformation matrix is valid

Returns:
Sthetaarray, 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.

Examples using pytransform3d.transformations.exponential_coordinates_from_transform

Plot Straight Line Paths

Plot Straight Line Paths

Plot Straight Line Paths
Invert Uncertain Transform

Invert Uncertain Transform

Invert Uncertain Transform
Concatenate Uncertain Transforms

Concatenate Uncertain Transforms

Concatenate Uncertain Transforms
Dual Quaternion Interpolation

Dual Quaternion Interpolation

Dual Quaternion Interpolation
Fuse 3 Poses

Fuse 3 Poses

Fuse 3 Poses