pub struct RigidBodyVelocity<T: SimdRealCopy> {
pub linvel: Vector<T>,
pub angvel: AngVector<T>,
}Expand description
The velocities of this rigid-body.
Fields§
§linvel: Vector<T>The linear velocity of the rigid-body.
angvel: AngVector<T>The angular velocity of the rigid-body.
Implementations§
Source§impl RigidBodyVelocity<f32>
impl RigidBodyVelocity<f32>
Sourcepub fn new(linvel: Vector<f32>, angvel: AngVector<f32>) -> Self
pub fn new(linvel: Vector<f32>, angvel: AngVector<f32>) -> Self
Create a new rigid-body velocity component.
Sourcepub fn from_slice(slice: &[f32]) -> Self
pub fn from_slice(slice: &[f32]) -> Self
Converts a slice to a rigid-body velocity.
The slice must contain at least 6 elements: the slice[0..3] contains
the linear velocity and the slice[3..6] contains the angular velocity.
Sourcepub fn as_slice(&self) -> &[f32]
pub fn as_slice(&self) -> &[f32]
This velocity seen as a slice.
The linear part is stored first.
Sourcepub fn as_mut_slice(&mut self) -> &mut [f32]
pub fn as_mut_slice(&mut self) -> &mut [f32]
This velocity seen as a mutable slice.
The linear part is stored first.
Sourcepub fn as_vector(&self) -> &Vector6<f32>
pub fn as_vector(&self) -> &Vector6<f32>
This velocity seen as a vector.
The linear part is stored first.
Sourcepub fn as_vector_mut(&mut self) -> &mut Vector6<f32>
pub fn as_vector_mut(&mut self) -> &mut Vector6<f32>
This velocity seen as a mutable vector.
The linear part is stored first.
Sourcepub fn transformed(self, rotation: &Rotation<f32>) -> Self
pub fn transformed(self, rotation: &Rotation<f32>) -> Self
Return self rotated by rotation.
Sourcepub fn pseudo_kinetic_energy(&self) -> f32
pub fn pseudo_kinetic_energy(&self) -> f32
The approximate kinetic energy of this rigid-body.
This approximation does not take the rigid-body’s mass and angular inertia into account. Some physics engines call this the “mass-normalized kinetic energy”.
Sourcepub fn velocity_at_point(
&self,
point: &Point<f32>,
world_com: &Point<f32>,
) -> Vector<f32>
pub fn velocity_at_point( &self, point: &Point<f32>, world_com: &Point<f32>, ) -> Vector<f32>
The velocity of the given world-space point on this rigid-body.
Sourcepub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> f32
pub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> f32
The kinetic energy of this rigid-body.
Sourcepub fn apply_impulse(
&mut self,
rb_mprops: &RigidBodyMassProps,
impulse: Vector<f32>,
)
pub fn apply_impulse( &mut self, rb_mprops: &RigidBodyMassProps, impulse: Vector<f32>, )
Applies an impulse at the center-of-mass of this rigid-body. The impulse is applied right away, changing the linear velocity. This does nothing on non-dynamic bodies.
Sourcepub fn apply_torque_impulse(
&mut self,
rb_mprops: &RigidBodyMassProps,
torque_impulse: Vector<f32>,
)
pub fn apply_torque_impulse( &mut self, rb_mprops: &RigidBodyMassProps, torque_impulse: Vector<f32>, )
Applies an angular impulse at the center-of-mass of this rigid-body. The impulse is applied right away, changing the angular velocity. This does nothing on non-dynamic bodies.
Sourcepub fn apply_impulse_at_point(
&mut self,
rb_mprops: &RigidBodyMassProps,
impulse: Vector<f32>,
point: Point<f32>,
)
pub fn apply_impulse_at_point( &mut self, rb_mprops: &RigidBodyMassProps, impulse: Vector<f32>, point: Point<f32>, )
Applies an impulse at the given world-space point of this rigid-body. The impulse is applied right away, changing the linear and/or angular velocities. This does nothing on non-dynamic bodies.
Source§impl<T: SimdRealCopy> RigidBodyVelocity<T>
impl<T: SimdRealCopy> RigidBodyVelocity<T>
Sourcepub fn apply_damping(&self, dt: T, damping: &RigidBodyDamping<T>) -> Self
pub fn apply_damping(&self, dt: T, damping: &RigidBodyDamping<T>) -> Self
Returns the update velocities after applying the given damping.
Sourcepub fn integrate(
&self,
dt: T,
init_pos: &Isometry<T>,
local_com: &Point<T>,
) -> Isometry<T>
pub fn integrate( &self, dt: T, init_pos: &Isometry<T>, local_com: &Point<T>, ) -> Isometry<T>
Integrate the velocities in self to compute obtain new positions when moving from the given
initial position init_pos.
Sourcepub fn integrate_centered(&self, dt: T, pose: Isometry<T>) -> Isometry<T>
pub fn integrate_centered(&self, dt: T, pose: Isometry<T>) -> Isometry<T>
Same as Self::integrate but with a local center-of-mass assumed to be zero.
Sourcepub fn integrate_linearized(&self, dt: T, pose: &mut Isometry<T>)
pub fn integrate_linearized(&self, dt: T, pose: &mut Isometry<T>)
Same as Self::integrate but with the angular part linearized and the local
center-of-mass assumed to be zero.
Trait Implementations§
Source§impl Add for RigidBodyVelocity<f32>
impl Add for RigidBodyVelocity<f32>
Source§impl AddAssign for RigidBodyVelocity<f32>
impl AddAssign for RigidBodyVelocity<f32>
Source§fn add_assign(&mut self, rhs: Self)
fn add_assign(&mut self, rhs: Self)
+= operation. Read moreSource§impl<T: Clone + SimdRealCopy> Clone for RigidBodyVelocity<T>
impl<T: Clone + SimdRealCopy> Clone for RigidBodyVelocity<T>
Source§fn clone(&self) -> RigidBodyVelocity<T>
fn clone(&self) -> RigidBodyVelocity<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 + SimdRealCopy> Debug for RigidBodyVelocity<T>
impl<T: Debug + SimdRealCopy> Debug for RigidBodyVelocity<T>
Source§impl Default for RigidBodyVelocity<f32>
impl Default for RigidBodyVelocity<f32>
Source§impl From<RigidBodyVelocity<f32>> for PdErrors
impl From<RigidBodyVelocity<f32>> for PdErrors
Source§fn from(vels: RigidBodyVelocity<f32>) -> Self
fn from(vels: RigidBodyVelocity<f32>) -> Self
Source§impl<T: PartialEq + SimdRealCopy> PartialEq for RigidBodyVelocity<T>
impl<T: PartialEq + SimdRealCopy> PartialEq for RigidBodyVelocity<T>
Source§impl Sub for RigidBodyVelocity<f32>
impl Sub for RigidBodyVelocity<f32>
Source§impl SubAssign for RigidBodyVelocity<f32>
impl SubAssign for RigidBodyVelocity<f32>
Source§fn sub_assign(&mut self, rhs: Self)
fn sub_assign(&mut self, rhs: Self)
-= operation. Read moreimpl<T: Copy + SimdRealCopy> Copy for RigidBodyVelocity<T>
impl<T: SimdRealCopy> StructuralPartialEq for RigidBodyVelocity<T>
Auto Trait Implementations§
impl<T> Freeze for RigidBodyVelocity<T>where
T: Freeze,
impl<T> RefUnwindSafe for RigidBodyVelocity<T>where
T: RefUnwindSafe,
impl<T> Send for RigidBodyVelocity<T>
impl<T> Sync for RigidBodyVelocity<T>
impl<T> Unpin for RigidBodyVelocity<T>where
T: Unpin,
impl<T> UnwindSafe for RigidBodyVelocity<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<T> Downcast for Twhere
T: Any,
impl<T> Downcast for Twhere
T: Any,
Source§fn into_any(self: Box<T>) -> Box<dyn Any>
fn into_any(self: Box<T>) -> Box<dyn Any>
Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>, which can then be
downcast into Box<dyn ConcreteType> where ConcreteType implements Trait.Source§fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
Rc<Trait> (where Trait: Downcast) to Rc<Any>, which can then be further
downcast into Rc<ConcreteType> where ConcreteType implements Trait.Source§fn as_any(&self) -> &(dyn Any + 'static)
fn as_any(&self) -> &(dyn Any + 'static)
&Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot
generate &Any’s vtable from &Trait’s.Source§fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
&mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot
generate &mut Any’s vtable from &mut Trait’s.Source§impl<T> DowncastSend for T
impl<T> DowncastSend for T
Source§impl<T> DowncastSync for T
impl<T> DowncastSync for T
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left is true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left(&self) returns true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§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.