pytransform3d.transformations.left_jacobian_SE3

pytransform3d.transformations.left_jacobian_SE3(Stheta)[source]

Left Jacobian of SE(3).

\boldsymbol{\mathcal{J}}
=
\left(
\begin{array}{cc}
\boldsymbol{J} & \boldsymbol{0}\\
\boldsymbol{Q} & \boldsymbol{J}
\end{array}
\right),

where \boldsymbol{J} is the left Jacobian of SO(3) and \boldsymbol{Q} is given by Barfoot and Furgale (see reference below).

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:
Jarray, shape (6, 6)

Jacobian of SE(3).

See also

left_jacobian_SE3_series

Left Jacobian of SE(3) at theta from Taylor series.

left_jacobian_SE3_inv

Left inverse Jacobian of SE(3).

References

Barfoot, Furgale: Associating Uncertainty With Three-Dimensional Poses for Use in Estimation Problems, http://ncfrn.mcgill.ca/members/pubs/barfoot_tro14.pdf