pytransform3d.transformations.transform_from_exponential_coordinates

pytransform3d.transformations.transform_from_exponential_coordinates(Stheta, check=True)[source]

Compute transformation matrix from exponential coordinates.

Exponential map.

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

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),

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

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.

checkbool, optional (default: True)

Check if exponential coordinates are valid

Returns:
A2Barray, shape (4, 4)

Transformation matrix from frame A to frame B

Examples using pytransform3d.transformations.transform_from_exponential_coordinates

Plot Transformation through Screw Motion

Plot Transformation through Screw Motion

Plot Transformation through Screw Motion
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
Visualize Cylinder with Wrench

Visualize Cylinder with Wrench

Visualize Cylinder with Wrench