pytransform3d.transformations
.left_jacobian_SE3_inv#
- pytransform3d.transformations.left_jacobian_SE3_inv(Stheta)[source]#
Left inverse Jacobian of SE(3).
\[\begin{split}\boldsymbol{\mathcal{J}}^{-1} = \left( \begin{array}{cc} \boldsymbol{J}^{-1} & \boldsymbol{0}\\ -\boldsymbol{J}^{-1}\boldsymbol{Q}\boldsymbol{J}^{-1} & \boldsymbol{J}^{-1} \end{array} \right),\end{split}\]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:
- J_invarray, shape (6, 6)
Inverse Jacobian of SE(3).
See also
left_jacobian_SE3
Left Jacobian of SE(3).
left_jacobian_SE3_inv_series
Left inverse Jacobian of SE(3) at theta from Taylor series.