pub struct SpatialInertia {
pub mass: f64,
pub com: Vec3,
pub inertia: Mat3,
}Expand description
Spatial inertia of a rigid body about its center of mass.
Stored as mass, center of mass offset, and rotational inertia. Can be converted to a 6x6 spatial inertia matrix.
Fields§
§mass: f64Mass of the body.
com: Vec3Center of mass position in body frame.
inertia: Mat3Rotational inertia about the center of mass (3x3 symmetric).
Implementations§
Source§impl SpatialInertia
impl SpatialInertia
Sourcepub fn new(mass: f64, com: Vec3, inertia: Mat3) -> Self
pub fn new(mass: f64, com: Vec3, inertia: Mat3) -> Self
Create a spatial inertia with the given mass, CoM offset, and inertia matrix.
Sourcepub fn point_mass(mass: f64, pos: Vec3) -> Self
pub fn point_mass(mass: f64, pos: Vec3) -> Self
Create spatial inertia for a point mass at a given position.
Sourcepub fn rod(mass: f64, length: f64) -> Self
pub fn rod(mass: f64, length: f64) -> Self
Create spatial inertia for a uniform rod of given mass and length along Y axis. Rod is centered at origin.
Sourcepub fn to_matrix(&self) -> SpatialMat
pub fn to_matrix(&self) -> SpatialMat
Convert to 6x6 spatial inertia matrix (about the body frame origin).
I_spatial = | I + m[c]×[c]×ᵀ m[c]× | | m[c]×ᵀ mE |
Sourcepub fn transform(&self, xform: &SpatialTransform) -> SpatialInertia
pub fn transform(&self, xform: &SpatialTransform) -> SpatialInertia
Transform this inertia to a new frame.
Trait Implementations§
Source§impl Clone for SpatialInertia
impl Clone for SpatialInertia
Source§fn clone(&self) -> SpatialInertia
fn clone(&self) -> SpatialInertia
Returns a duplicate of the value. Read more
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source. Read moreSource§impl Debug for SpatialInertia
impl Debug for SpatialInertia
impl Copy for SpatialInertia
Auto Trait Implementations§
impl Freeze for SpatialInertia
impl RefUnwindSafe for SpatialInertia
impl Send for SpatialInertia
impl Sync for SpatialInertia
impl Unpin for SpatialInertia
impl UnsafeUnpin for SpatialInertia
impl UnwindSafe for SpatialInertia
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
Mutably borrows from an owned value. Read more
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>
The inverse inclusion map: attempts to construct
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
Checks if
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
Use with care! Same as
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self to the equivalent element of its superset.