[−][src]Struct cv_core::Skew3
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).
Methods
impl Skew3
[src]
pub fn rotation(self) -> Rotation3<f64>
[src]
Converts the Skew3 to a Rotation3 matrix.
pub fn vee(mat: Matrix3<f64>) -> Self
[src]
This converts a matrix in skew-symmetric form into a Skew3.
Warning: Does no check to ensure matrix is actually skew-symmetric.
pub fn hat(self) -> Matrix3<f64>
[src]
This converts the Skew3 into its skew-symmetric matrix form.
pub fn hat2(self) -> Matrix3<f64>
[src]
This converts the Skew3 into its squared skew-symmetric matrix form efficiently.
pub fn bracket(self, rhs: Self) -> Self
[src]
Computes the lie bracket [self, rhs].
pub fn jacobian_output_to_input(self) -> Matrix3<f64>
[src]
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).
pub fn jacobian_output_to_self(y: Vector3<f64>) -> Matrix3<f64>
[src]
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
.
Trait Implementations
impl AbstractRotation<f64, U3> for Skew3
[src]
fn identity() -> Self
[src]
fn inverse(&self) -> Self
[src]
fn inverse_mut(&mut self)
[src]
fn transform_vector(&self, v: &Vector3<f64>) -> Vector3<f64>
[src]
fn transform_point(&self, p: &Point3<f64>) -> Point3<f64>
[src]
fn inverse_transform_vector(&self, v: &Vector3<f64>) -> Vector3<f64>
[src]
fn inverse_transform_point(&self, p: &Point3<f64>) -> Point3<f64>
[src]
impl AsMut<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3, U1>>::Buffer>> for Skew3
[src]
impl AsRef<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3, U1>>::Buffer>> for Skew3
[src]
impl Clone for Skew3
[src]
fn clone(&self) -> Skew3
[src]
fn clone_from(&mut self, source: &Self)
1.0.0[src]
impl Copy for Skew3
[src]
impl Debug for Skew3
[src]
impl Deref for Skew3
[src]
type Target = Vector3<f64>
The resulting type after dereferencing.
fn deref(&self) -> &Self::Target
[src]
impl DerefMut for Skew3
[src]
impl From<Matrix<f64, U3, U1, <DefaultAllocator as Allocator<f64, U3, U1>>::Buffer>> for Skew3
[src]
impl From<Rotation<f64, U3>> for Skew3
[src]
This is the log map.
impl From<Skew3> for Vector3<f64>
[src]
impl From<Skew3> for Rotation3<f64>
[src]
This is the exponential map.
impl Mul<Skew3> for Skew3
[src]
type Output = Self
The resulting type after applying the *
operator.
fn mul(self, rhs: Self) -> Self
[src]
impl MulAssign<Skew3> for Skew3
[src]
fn mul_assign(&mut self, rhs: Self)
[src]
impl PartialEq<Skew3> for Skew3
[src]
impl PartialOrd<Skew3> for Skew3
[src]
fn partial_cmp(&self, other: &Skew3) -> Option<Ordering>
[src]
fn lt(&self, other: &Skew3) -> bool
[src]
fn le(&self, other: &Skew3) -> bool
[src]
fn gt(&self, other: &Skew3) -> bool
[src]
fn ge(&self, other: &Skew3) -> bool
[src]
impl StructuralPartialEq for Skew3
[src]
Auto Trait Implementations
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
fn borrow_mut(&mut self) -> &mut T
[src]
impl<T, Right> ClosedMul<Right> for T where
T: Mul<Right, Output = T> + MulAssign<Right>,
T: Mul<Right, Output = T> + MulAssign<Right>,
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<T> Scalar for T where
T: PartialEq<T> + Copy + Any + Debug,
[src]
T: PartialEq<T> + Copy + Any + Debug,
fn inlined_clone(&self) -> T
[src]
fn is<T>() -> bool where
T: Scalar,
[src]
T: Scalar,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
fn to_subset(&self) -> Option<SS>
fn is_in_subset(&self) -> bool
fn to_subset_unchecked(&self) -> SS
fn from_subset(element: &SS) -> SP
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,