[−][src]Function opencv::calib3d::rodrigues
pub fn rodrigues(
src: &dyn ToInputArray,
dst: &mut dyn ToOutputArray,
jacobian: &mut dyn ToOutputArray
) -> Result<()>
Converts a rotation matrix to a rotation vector or vice versa.
Parameters
- src: Input rotation vector (3x1 or 1x3) or rotation matrix (3x3).
- dst: Output rotation matrix (3x3) or rotation vector (3x1 or 1x3), respectively.
- jacobian: Optional output Jacobian matrix, 3x9 or 9x3, which is a matrix of partial derivatives of the output array components with respect to the input array components.
Inverse transformation can be also done easily, since
A rotation vector is a convenient and most compact representation of a rotation matrix (since any rotation matrix has just 3 degrees of freedom). The representation is used in the global 3D geometry optimization procedures like @ref calibrateCamera, @ref stereoCalibrate, or @ref solvePnP .
Note: More information about the computation of the derivative of a 3D rotation matrix with respect to its exponential coordinate can be found in:
- A Compact Formula for the Derivative of a 3-D Rotation in Exponential Coordinates, Guillermo Gallego, Anthony J. Yezzi Gallego2014ACF
Note: Useful information on SE(3) and Lie Groups can be found in:
- A tutorial on SE(3) transformation parameterizations and on-manifold optimization, Jose-Luis Blanco blanco2010tutorial
- Lie Groups for 2D and 3D Transformation, Ethan Eade Eade17
- A micro Lie theory for state estimation in robotics, Joan Solà, Jérémie Deray, Dinesh Atchuthan Sol2018AML
C++ default parameters
- jacobian: noArray()