pub struct SpatialTransform {
pub rot: Mat3,
pub pos: Vec3,
}Expand description
Plücker transform: rigid body transformation acting on spatial vectors.
Represents a coordinate transform from frame A to frame B. Stored as rotation R and translation p (position of B’s origin in A’s frame).
Fields§
§rot: Mat3Rotation from frame A to frame B.
pos: Vec3Position of frame B’s origin expressed in frame A.
Implementations§
Source§impl SpatialTransform
impl SpatialTransform
Sourcepub fn translation(pos: Vec3) -> Self
pub fn translation(pos: Vec3) -> Self
Pure translation.
Sourcepub fn to_motion_matrix(&self) -> Mat6
pub fn to_motion_matrix(&self) -> Mat6
Get the 6x6 Plücker transform matrix for motion vectors.
X = | R 0 | | -R[p]× R |
This transforms spatial motion vectors from frame A to frame B.
Sourcepub fn to_force_matrix(&self) -> Mat6
pub fn to_force_matrix(&self) -> Mat6
Get the 6x6 Plücker transform matrix for force vectors.
X* = | R -R[p]× | | 0 R |
This is the transpose-inverse of the motion transform.
Sourcepub fn apply_motion(&self, v: &SpatialVec) -> SpatialVec
pub fn apply_motion(&self, v: &SpatialVec) -> SpatialVec
Transform a spatial motion vector from frame A to frame B.
Sourcepub fn apply_force(&self, f: &SpatialVec) -> SpatialVec
pub fn apply_force(&self, f: &SpatialVec) -> SpatialVec
Transform a spatial force vector from frame A to frame B.
Sourcepub fn inv_apply_motion(&self, v: &SpatialVec) -> SpatialVec
pub fn inv_apply_motion(&self, v: &SpatialVec) -> SpatialVec
Inverse transform a spatial motion vector (from B to A).
Sourcepub fn inv_apply_force(&self, f: &SpatialVec) -> SpatialVec
pub fn inv_apply_force(&self, f: &SpatialVec) -> SpatialVec
Inverse transform a spatial force vector (from B to A).
Sourcepub fn compose(&self, other: &SpatialTransform) -> SpatialTransform
pub fn compose(&self, other: &SpatialTransform) -> SpatialTransform
Compose two transforms: self ∘ other.
Sourcepub fn inverse(&self) -> SpatialTransform
pub fn inverse(&self) -> SpatialTransform
Inverse of this transform.
Sourcepub fn translation_vector(&self) -> Vec3
pub fn translation_vector(&self) -> Vec3
Get the translation vector.
Sourcepub fn rotation_matrix(&self) -> Mat3
pub fn rotation_matrix(&self) -> Mat3
Get the rotation matrix.
Trait Implementations§
Source§impl Clone for SpatialTransform
impl Clone for SpatialTransform
Source§fn clone(&self) -> SpatialTransform
fn clone(&self) -> SpatialTransform
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for SpatialTransform
impl Debug for SpatialTransform
impl Copy for SpatialTransform
Auto Trait Implementations§
impl Freeze for SpatialTransform
impl RefUnwindSafe for SpatialTransform
impl Send for SpatialTransform
impl Sync for SpatialTransform
impl Unpin for SpatialTransform
impl UnsafeUnpin for SpatialTransform
impl UnwindSafe for SpatialTransform
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.