pub struct Skew3(pub Vector3<f64>);
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§
Source§impl Skew3
impl Skew3
Sourcepub fn vee(mat: Matrix3<f64>) -> Self
pub fn vee(mat: Matrix3<f64>) -> Self
This converts a matrix in skew-symmetric form into a Skew3.
Warning: Does no check to ensure matrix is actually skew-symmetric.
Sourcepub fn hat2(self) -> Matrix3<f64>
pub fn hat2(self) -> Matrix3<f64>
This converts the Skew3 into its squared skew-symmetric matrix form efficiently.
Sourcepub fn jacobian_input(self) -> Matrix4<f64>
pub fn jacobian_input(self) -> Matrix4<f64>
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.
Sourcepub fn jacobian_self(y: Vector3<f64>) -> Matrix3<f64>
pub fn jacobian_self(y: Vector3<f64>) -> Matrix3<f64>
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§
Source§impl PartialOrd for Skew3
impl PartialOrd for Skew3
impl Copy for Skew3
impl StructuralPartialEq for Skew3
Auto Trait Implementations§
impl Freeze for Skew3
impl RefUnwindSafe for Skew3
impl Send for Skew3
impl Sync for Skew3
impl Unpin for Skew3
impl UnwindSafe for Skew3
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.