pub struct SpatialVector<T = ()> {
pub top: Vec3,
pub bottom: Vec3,
/* private fields */
}Expand description
A 6D spatial vector representing either motion or force.
Fields§
§top: Vec3The top (angular) component of the spatial vector.
- For motion vectors: angular velocity ω
- For force vectors: moment/torque n
bottom: Vec3The bottom (linear) component of the spatial vector.
- For motion vectors: linear velocity v
- For force vectors: force f
Implementations§
Source§impl<T> SpatialVector<T>
impl<T> SpatialVector<T>
Sourcepub const ZERO: Self
pub const ZERO: Self
Zero spatial vector (both angular and linear components are zero).
This is useful for initialization and as the identity element for vector addition operations.
Sourcepub const fn from_array(array: [Real; 6]) -> Self
pub const fn from_array(array: [Real; 6]) -> Self
Create a spatial vector from a 6-element array.
§Array Format
- Motion vectors: [ωx, ωy, ωz, vx, vy, vz] where ω is angular velocity and v is linear velocity
- Force vectors: [nx, ny, nz, fx, fy, fz] where n is moment/torque and f is force
§Example
use spatial_math::SpatialMotionVector;
let velocity = SpatialMotionVector::from_array([1.0, 0.0, 0.0, 0.0, 1.0, 0.0]);
// ω = [1, 0, 0], v = [0, 1, 0]Sourcepub fn from_vec6(vec: SVector<6>) -> Self
pub fn from_vec6(vec: SVector<6>) -> Self
Create a spatial vector from a 6D static vector.
This is useful when converting from other linear algebra
representations that use SVector<6>.
Sourcepub const fn from_pair(top: Vec3, bottom: Vec3) -> Self
pub const fn from_pair(top: Vec3, bottom: Vec3) -> Self
Create a spatial vector from separate 3D top and bottom components.
This is often used when you have separate angular and linear quantities that need to be combined into a spatial vector.
§Arguments
top- The angular component (ω for motion, n for force)bottom- The linear component (v for motion, f for force)
Sourcepub fn into_array(self) -> [Real; 6]
pub fn into_array(self) -> [Real; 6]
Convert the spatial vector to a 6-element array.
Returns the components in the same format as expected by from_array():
[top.x, top.y, top.z, bottom.x, bottom.y, bottom.z]
pub fn any_nan(&self) -> bool
pub fn add(&self, rhs: &Self) -> Self
pub fn sub(&self, rhs: &Self) -> Self
pub fn neg(&self) -> Self
pub fn scale(&self, scalar: Real) -> Self
pub fn cross(&self, rhs: &Self) -> Self
pub fn into_vec6(self) -> SVector<6>
Trait Implementations§
Source§impl<T> Add for SpatialVector<T>
impl<T> Add for SpatialVector<T>
Source§impl<T> AddAssign for SpatialVector<T>
impl<T> AddAssign for SpatialVector<T>
Source§fn add_assign(&mut self, rhs: Self)
fn add_assign(&mut self, rhs: Self)
+= operation. Read moreSource§impl<T: Clone> Clone for SpatialVector<T>
impl<T: Clone> Clone for SpatialVector<T>
Source§fn clone(&self) -> SpatialVector<T>
fn clone(&self) -> SpatialVector<T>
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl<T: Debug> Debug for SpatialVector<T>
impl<T: Debug> Debug for SpatialVector<T>
Source§impl<T: Default> Default for SpatialVector<T>
impl<T: Default> Default for SpatialVector<T>
Source§fn default() -> SpatialVector<T>
fn default() -> SpatialVector<T>
Source§impl<T> Display for SpatialVector<T>
impl<T> Display for SpatialVector<T>
Source§impl<T> From<SpatialVector<T>> for Vec6
impl<T> From<SpatialVector<T>> for Vec6
Source§fn from(v: SpatialVector<T>) -> Self
fn from(v: SpatialVector<T>) -> Self
Source§impl Mul<SpatialVector<Force>> for PluckerTransform
impl Mul<SpatialVector<Force>> for PluckerTransform
Source§type Output = SpatialVector<Force>
type Output = SpatialVector<Force>
* operator.Source§fn mul(self, rhs: SpatialForceVector) -> SpatialForceVector
fn mul(self, rhs: SpatialForceVector) -> SpatialForceVector
* operation. Read moreSource§impl Mul<SpatialVector<Motion>> for &ArticulatedBodyInertia
impl Mul<SpatialVector<Motion>> for &ArticulatedBodyInertia
Source§type Output = SpatialVector<Force>
type Output = SpatialVector<Force>
* operator.Source§impl Mul<SpatialVector<Motion>> for ArticulatedBodyInertia
impl Mul<SpatialVector<Motion>> for ArticulatedBodyInertia
Source§type Output = SpatialVector<Force>
type Output = SpatialVector<Force>
* operator.Source§impl Mul<SpatialVector<Motion>> for PluckerTransform
impl Mul<SpatialVector<Motion>> for PluckerTransform
Source§type Output = SpatialVector<Motion>
type Output = SpatialVector<Motion>
* operator.Source§fn mul(self, rhs: SpatialMotionVector) -> SpatialMotionVector
fn mul(self, rhs: SpatialMotionVector) -> SpatialMotionVector
* operation. Read moreSource§impl Mul<SpatialVector<Motion>> for RigidBodyInertia
impl Mul<SpatialVector<Motion>> for RigidBodyInertia
Source§type Output = SpatialVector<Force>
type Output = SpatialVector<Force>
* operator.Source§impl<T> Mul<f32> for SpatialVector<T>
impl<T> Mul<f32> for SpatialVector<T>
Source§impl<T> Neg for SpatialVector<T>
impl<T> Neg for SpatialVector<T>
Source§impl<T: PartialEq> PartialEq for SpatialVector<T>
impl<T: PartialEq> PartialEq for SpatialVector<T>
Source§impl<T> Sub for SpatialVector<T>
impl<T> Sub for SpatialVector<T>
Source§impl<T> SubAssign for SpatialVector<T>
impl<T> SubAssign for SpatialVector<T>
Source§fn sub_assign(&mut self, rhs: Self)
fn sub_assign(&mut self, rhs: Self)
-= operation. Read moreimpl<T: Copy> Copy for SpatialVector<T>
impl<T> StructuralPartialEq for SpatialVector<T>
Auto Trait Implementations§
impl<T> Freeze for SpatialVector<T>
impl<T> RefUnwindSafe for SpatialVector<T>where
T: RefUnwindSafe,
impl<T> Send for SpatialVector<T>where
T: Send,
impl<T> Sync for SpatialVector<T>where
T: Sync,
impl<T> Unpin for SpatialVector<T>where
T: Unpin,
impl<T> UnwindSafe for SpatialVector<T>where
T: UnwindSafe,
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.