Struct cv_core::Skew3 [−][src]
Expand description
Contains a member of the lie algebra so(3), a representation of the tangent space of 3d rotation. This is also known as the lie algebra of the 3d rotation group SO(3).
This is only intended to be used in optimization problems where it is desirable to have unconstranied variables representing the degrees of freedom of the rotation. In all other cases, a rotation matrix should be used to store rotations, since the conversion to and from a rotation matrix is non-trivial.
Tuple Fields
0: Vector3<f64>
Implementations
This converts a matrix in skew-symmetric form into a Skew3.
Warning: Does no check to ensure matrix is actually skew-symmetric.
This converts the Skew3 into its squared skew-symmetric matrix form efficiently.
The jacobian of the output of a rotation in respect to the input of a rotation.
y = R * x
dy/dx = R
The formula is pretty simple and is just the rotation matrix created
from the exponential map of this so(3) element into SO(3). The result is converted
to homogeneous form (by adding a new dimension with a 1
in the diagonal) so
that it is compatible with homogeneous coordinates.
If you have the rotation matrix already, please use the rotation matrix itself
rather than calling this method. Calling this method will waste time converting
the Skew3
back into a Rotation3
, which is non-trivial.
The jacobian of the output of a rotation in respect to the rotation itself.
y = R * x
dy/dR = -hat(y)
The derivative is purely based on the current output vector, and thus doesn’t take self
.
Note that when working with homogeneous projective coordinates, only the first three components
(the bearing) are relevant, hence the resulting matrix is a Matrix3
.
Trait Implementations
This is the log map.
This is the exponential map.
This method returns an ordering between self
and other
values if one exists. Read more
This method tests less than (for self
and other
) and is used by the <
operator. Read more
This method tests less than or equal to (for self
and other
) and is used by the <=
operator. Read more
This method tests greater than (for self
and other
) and is used by the >
operator. Read more
Auto Trait Implementations
impl RefUnwindSafe for Skew3
impl UnwindSafe for Skew3
Blanket Implementations
Mutably borrows from an owned value. Read more
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
Checks if self
is actually part of its subset T
(and can be converted to it).
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
The inclusion map: converts self
to the equivalent element of its superset.