pub struct RigidBodyVelocity {
pub linvel: Vector<f32>,
pub angvel: AngVector<f32>,
}
Expand description
The velocities of this rigid-body.
Fields§
§linvel: Vector<f32>
The linear velocity of the rigid-body.
angvel: AngVector<f32>
The angular velocity of the rigid-body.
Implementations§
Source§impl RigidBodyVelocity
impl RigidBodyVelocity
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 3 elements: the slice[0..2]
contains
the linear velocity and the slice[2]
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) -> &Vector3<f32>
pub fn as_vector(&self) -> &Vector3<f32>
This velocity seen as a vector.
The linear part is stored first.
Sourcepub fn as_vector_mut(&mut self) -> &mut Vector3<f32>
pub fn as_vector_mut(&mut self) -> &mut Vector3<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 apply_damping(&self, dt: f32, damping: &RigidBodyDamping) -> Self
pub fn apply_damping(&self, dt: f32, damping: &RigidBodyDamping) -> Self
Returns the update velocities after applying the given damping.
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 integrate(
&self,
dt: f32,
init_pos: &Isometry<f32>,
local_com: &Point<f32>,
) -> Isometry<f32>
pub fn integrate( &self, dt: f32, init_pos: &Isometry<f32>, local_com: &Point<f32>, ) -> Isometry<f32>
Integrate the velocities in self
to compute obtain new positions when moving from the given
initial position init_pos
.
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: f32,
)
pub fn apply_torque_impulse( &mut self, rb_mprops: &RigidBodyMassProps, torque_impulse: 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.
Trait Implementations§
Source§impl Add for RigidBodyVelocity
impl Add for RigidBodyVelocity
Source§impl AddAssign for RigidBodyVelocity
impl AddAssign for RigidBodyVelocity
Source§fn add_assign(&mut self, rhs: Self)
fn add_assign(&mut self, rhs: Self)
+=
operation. Read moreSource§impl Clone for RigidBodyVelocity
impl Clone for RigidBodyVelocity
Source§fn clone(&self) -> RigidBodyVelocity
fn clone(&self) -> RigidBodyVelocity
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for RigidBodyVelocity
impl Debug for RigidBodyVelocity
Source§impl Default for RigidBodyVelocity
impl Default for RigidBodyVelocity
Source§impl From<RigidBodyVelocity> for PdErrors
impl From<RigidBodyVelocity> for PdErrors
Source§fn from(vels: RigidBodyVelocity) -> Self
fn from(vels: RigidBodyVelocity) -> Self
Source§impl Mul<f32> for RigidBodyVelocity
impl Mul<f32> for RigidBodyVelocity
Source§impl PartialEq for RigidBodyVelocity
impl PartialEq for RigidBodyVelocity
Source§impl Sub for RigidBodyVelocity
impl Sub for RigidBodyVelocity
Source§impl SubAssign for RigidBodyVelocity
impl SubAssign for RigidBodyVelocity
Source§fn sub_assign(&mut self, rhs: Self)
fn sub_assign(&mut self, rhs: Self)
-=
operation. Read moreimpl Copy for RigidBodyVelocity
impl StructuralPartialEq for RigidBodyVelocity
Auto Trait Implementations§
impl Freeze for RigidBodyVelocity
impl RefUnwindSafe for RigidBodyVelocity
impl Send for RigidBodyVelocity
impl Sync for RigidBodyVelocity
impl Unpin for RigidBodyVelocity
impl UnwindSafe for RigidBodyVelocity
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>
. Box<dyn Any>
can
then be further downcast
into Box<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>
. Rc<Any>
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> 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<T> Pointable for T
impl<T> Pointable for T
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.