Struct rapier3d::dynamics::RigidBodyVelocity
source · [−]Expand description
The velocities of this rigid-body.
Fields
linvel: Vector<Real>
The linear velocity of the rigid-body.
angvel: AngVector<Real>
The angular velocity of the rigid-body.
Implementations
sourceimpl RigidBodyVelocity
impl RigidBodyVelocity
sourcepub fn new(linvel: Vector<Real>, angvel: AngVector<Real>) -> Self
pub fn new(linvel: Vector<Real>, angvel: AngVector<Real>) -> Self
Create a new rigid-body velocity component.
sourcepub fn from_slice(slice: &[Real]) -> Self
pub fn from_slice(slice: &[Real]) -> 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) -> &[Real]
pub fn as_slice(&self) -> &[Real]
This velocity seen as a slice.
The linear part is stored first.
sourcepub fn as_mut_slice(&mut self) -> &mut [Real]
pub fn as_mut_slice(&mut self) -> &mut [Real]
This velocity seen as a mutable slice.
The linear part is stored first.
sourcepub fn as_vector(&self) -> &Vector6<Real>
pub fn as_vector(&self) -> &Vector6<Real>
This velocity seen as a vector.
The linear part is stored first.
sourcepub fn as_vector_mut(&mut self) -> &mut Vector6<Real>
pub fn as_vector_mut(&mut self) -> &mut Vector6<Real>
This velocity seen as a mutable vector.
The linear part is stored first.
sourcepub fn transformed(self, rotation: &Rotation<Real>) -> Self
pub fn transformed(self, rotation: &Rotation<Real>) -> Self
Return self
rotated by rotation
.
sourcepub fn pseudo_kinetic_energy(&self) -> Real
pub fn pseudo_kinetic_energy(&self) -> Real
The approximate kinetic energy of this rigid-body.
This approximation does not take the rigid-body’s mass and angular inertia into account.
sourcepub fn apply_damping(&self, dt: Real, damping: &RigidBodyDamping) -> Self
pub fn apply_damping(&self, dt: Real, damping: &RigidBodyDamping) -> Self
Returns the update velocities after applying the given damping.
sourcepub fn velocity_at_point(
&self,
point: &Point<Real>,
world_com: &Point<Real>
) -> Vector<Real>
pub fn velocity_at_point(
&self,
point: &Point<Real>,
world_com: &Point<Real>
) -> Vector<Real>
The velocity of the given world-space point on this rigid-body.
sourcepub fn integrate(
&self,
dt: Real,
init_pos: &Isometry<Real>,
local_com: &Point<Real>
) -> Isometry<Real>
pub fn integrate(
&self,
dt: Real,
init_pos: &Isometry<Real>,
local_com: &Point<Real>
) -> Isometry<Real>
Integrate the velocities in self
to compute obtain new positions when moving from the given
inital position init_pos
.
sourcepub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> Real
pub fn kinetic_energy(&self, rb_mprops: &RigidBodyMassProps) -> Real
The kinetic energy of this rigid-body.
sourcepub fn apply_impulse(
&mut self,
rb_mprops: &RigidBodyMassProps,
impulse: Vector<Real>
)
pub fn apply_impulse(
&mut self,
rb_mprops: &RigidBodyMassProps,
impulse: Vector<Real>
)
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<Real>
)
pub fn apply_torque_impulse(
&mut self,
rb_mprops: &RigidBodyMassProps,
torque_impulse: Vector<Real>
)
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<Real>,
point: Point<Real>
)
pub fn apply_impulse_at_point(
&mut self,
rb_mprops: &RigidBodyMassProps,
impulse: Vector<Real>,
point: Point<Real>
)
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
sourceimpl Add<RigidBodyVelocity> for RigidBodyVelocity
impl Add<RigidBodyVelocity> for RigidBodyVelocity
type Output = RigidBodyVelocity
type Output = RigidBodyVelocity
The resulting type after applying the +
operator.
sourceimpl AddAssign<RigidBodyVelocity> for RigidBodyVelocity
impl AddAssign<RigidBodyVelocity> for RigidBodyVelocity
sourcefn add_assign(&mut self, rhs: Self)
fn add_assign(&mut self, rhs: Self)
Performs the +=
operation. Read more
sourceimpl Clone for RigidBodyVelocity
impl Clone for RigidBodyVelocity
sourcefn clone(&self) -> RigidBodyVelocity
fn clone(&self) -> RigidBodyVelocity
Returns a copy of the value. Read more
1.0.0 · sourcefn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from source
. Read more
sourceimpl Debug for RigidBodyVelocity
impl Debug for RigidBodyVelocity
sourceimpl Default for RigidBodyVelocity
impl Default for RigidBodyVelocity
sourceimpl Mul<f32> for RigidBodyVelocity
impl Mul<f32> for RigidBodyVelocity
sourceimpl PartialEq<RigidBodyVelocity> for RigidBodyVelocity
impl PartialEq<RigidBodyVelocity> for RigidBodyVelocity
sourcefn eq(&self, other: &RigidBodyVelocity) -> bool
fn eq(&self, other: &RigidBodyVelocity) -> bool
This method tests for self
and other
values to be equal, and is used
by ==
. Read more
sourcefn ne(&self, other: &RigidBodyVelocity) -> bool
fn ne(&self, other: &RigidBodyVelocity) -> bool
This method tests for !=
.
impl Copy for RigidBodyVelocity
impl StructuralPartialEq for RigidBodyVelocity
Auto Trait Implementations
impl RefUnwindSafe for RigidBodyVelocity
impl Send for RigidBodyVelocity
impl Sync for RigidBodyVelocity
impl Unpin for RigidBodyVelocity
impl UnwindSafe for RigidBodyVelocity
Blanket Implementations
sourceimpl<T> BorrowMut<T> for T where
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
const: unstable · sourcefn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
sourceimpl<T> Downcast for T where
T: Any,
impl<T> Downcast for T where
T: Any,
sourcefn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>
fn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>
Convert 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
. Read more
sourcefn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
Convert Rc<Trait>
(where Trait: Downcast
) to Rc<Any>
. Rc<Any>
can then be
further downcast
into Rc<ConcreteType>
where ConcreteType
implements Trait
. Read more
sourcefn as_any(&self) -> &(dyn Any + 'static)
fn as_any(&self) -> &(dyn Any + 'static)
Convert &Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &Any
’s vtable from &Trait
’s. Read more
sourcefn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
Convert &mut Trait
(where Trait: Downcast
) to &Any
. This is needed since Rust cannot
generate &mut Any
’s vtable from &mut Trait
’s. Read more
sourceimpl<T> DowncastSync for T where
T: Any + Send + Sync,
impl<T> DowncastSync for T where
T: Any + Send + Sync,
impl<T> Pointable for T
impl<T> Pointable for T
sourceimpl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
sourcefn 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 more
sourcefn 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).
sourcefn 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.
sourcefn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.
sourceimpl<T> ToOwned for T where
T: Clone,
impl<T> ToOwned for T where
T: Clone,
type Owned = T
type Owned = T
The resulting type after obtaining ownership.
sourcefn clone_into(&self, target: &mut T)
fn clone_into(&self, target: &mut T)
toowned_clone_into
)Uses borrowed data to replace owned data, usually by cloning. Read more