RigidBody

Struct RigidBody 

Source
pub struct RigidBody<N: RealField + Copy> { /* private fields */ }
Expand description

A rigid body.

Implementations§

Source§

impl<N: RealField + Copy> RigidBody<N>

Source

pub fn user_data(&self) -> Option<&(dyn Any + Send + Sync)>

Retrieves a reference to the user-defined user-data attached to this object.

Source

pub fn user_data_mut(&mut self) -> Option<&mut (dyn Any + Send + Sync)>

Retrieves a mutable reference to the user-defined user-data attached to this object.

Source

pub fn set_user_data( &mut self, data: Option<Box<dyn Any + Send + Sync>>, ) -> Option<Box<dyn Any + Send + Sync>>

Sets the user-defined data attached to this object.

Source

pub fn take_user_data(&mut self) -> Option<Box<dyn Any + Send + Sync>>

Replace by None the user-defined data attached to this object and returns the old value.

Source

pub fn linear_motion_interpolation_enabled(&self) -> bool

Check if linear motion interpolation is enabled for CCD.

If this is disabled, non-linear interpolation will be used.

Source

pub fn enable_linear_motion_interpolation(&mut self, enabled: bool)

Enable linear motion interpolation for CCD.

If this is disabled, non-linear interpolation will be used.

Source

pub fn set_translations_kinematic(&mut self, is_kinematic: Vector<bool>)

Mark some translational degrees of freedom as kinematic.

Source

pub fn set_rotations_kinematic(&mut self, is_kinematic: bool)

Mark rotations as kinematic.

Source

pub fn kinematic_translations(&self) -> Vector<bool>

Flags indicating which translational degrees of freedoms are kinematic.

Source

pub fn kinematic_rotations(&self) -> bool

Flags indicating if rotations are kinematic.

Source

pub fn disable_all_rotations(&mut self)

Disable all rotations of this rigid body.

This is the same as setting all the rotations of this rigid body as kinematic and setting its angular velocity to zero. The rotations will still be controllable at the velocity level by the user afterwards.

Source

pub fn enable_all_rotations(&mut self)

Enable all rotations for this rigid body.

This is the same as setting all the rotations of this rigid body as non-kinematic.

Source

pub fn disable_all_translations(&mut self)

Disable all translations of this rigid body.

This is the same as setting all the translations of this rigid body as kinematic and setting its linear velocity to zero. The translations will still be controllable at the velocity level by the user afterwards.

Source

pub fn enable_all_translations(&mut self)

Enable all translations for this rigid body.

This is the same as setting all the translations of this rigid body as non-kinematic.

Source

pub fn set_linear_damping(&mut self, damping: N)

Sets the linear damping coefficient of this rigid body.

Linear damping will make the rigid body loose linear velocity automatically velocity at each timestep. There is no damping by default.

Source

pub fn linear_damping(&self) -> N

The linear damping coefficient of this rigid body.

Source

pub fn set_angular_damping(&mut self, damping: N)

Sets the angular damping coefficient of this rigid body.

Angular damping will make the rigid body loose angular velocity automatically velocity at each timestep. There is no damping by default.

Source

pub fn angular_damping(&self) -> N

The angular damping coefficient of this rigid body.

Source

pub fn set_max_linear_velocity(&mut self, max_vel: N)

Caps the linear velocity of this rigid body to the given maximum.

This will prevent a rigid body from having a linear velocity with magnitude greater than max_vel.

Source

pub fn max_linear_velocity(&self) -> N

The maximum allowed linear velocity of this rigid body.

Source

pub fn set_max_angular_velocity(&mut self, max_vel: N)

Caps the angular velocity of this rigid body to the given maximum.

This will prevent a rigid body from having a angular velocity with magnitude greater than max_vel.

Source

pub fn max_angular_velocity(&self) -> N

The maximum allowed angular velocity of this rigid body.

Source

pub fn activation_status_mut(&mut self) -> &mut ActivationStatus<N>

Mutable information regarding activation and deactivation (sleeping) of this rigid body.

Source

pub fn set_local_center_of_mass(&mut self, local_com: Point<N>)

Set the center of mass of this rigid body, expressed in its local space.

Source

pub fn set_local_inertia(&mut self, local_inertia: Inertia<N>)

Set the local inertia of this rigid body, expressed in its local space.

Source

pub fn set_mass(&mut self, mass: N)

Set the mass of this rigid body.

Source

pub fn set_angular_inertia(&mut self, angular_inertia: N)

Set the angular inertia of this rigid body, expressed in its local space.

Source

pub fn set_position(&mut self, pos: Isometry<N>)

Sets the position of this rigid body.

Source

pub fn set_velocity(&mut self, vel: Velocity<N>)

Set the velocity of this rigid body.

Source

pub fn set_linear_velocity(&mut self, vel: Vector<N>)

Set the linear velocity of this rigid body.

Source

pub fn set_angular_velocity(&mut self, vel: N)

Set the angular velocity of this rigid body.

Source

pub fn augmented_mass(&self) -> &Inertia<N>

The augmented mass (inluding gyroscropic terms) in world-space of this rigid body.

Source

pub fn inv_augmented_mass(&self) -> &Inertia<N>

The inverse augmented mass (inluding gyroscropic terms) in world-space of this rigid body.

Source

pub fn position(&self) -> &Isometry<N>

The position of this rigid body.

Source

pub fn velocity(&self) -> &Velocity<N>

The velocity of this rigid body.

Trait Implementations§

Source§

impl<N: RealField + Copy> Body<N> for RigidBody<N>

Source§

fn activation_status(&self) -> &ActivationStatus<N>

Information regarding activation and deactivation (sleeping) of this body.
Source§

fn activate_with_energy(&mut self, energy: N)

Force the activation of this body with the given level of energy.
Source§

fn deactivate(&mut self)

Put this body to sleep.
Source§

fn set_deactivation_threshold(&mut self, threshold: Option<N>)

Sets the energy bellow which this body is put to sleep. Read more
Source§

fn update_status(&self) -> BodyUpdateStatus

The flags tracking what modifications were applied to a body.
Source§

fn status(&self) -> BodyStatus

The status of this body.
Source§

fn set_status(&mut self, status: BodyStatus)

Set the status of this body.
Source§

fn deformed_positions(&self) -> Option<(DeformationsType, &[N])>

If this is a deformable body, returns its deformed positions.
Source§

fn deformed_positions_mut(&mut self) -> Option<(DeformationsType, &mut [N])>

If this is a deformable body, returns a mutable reference to its deformed positions.
Source§

fn companion_id(&self) -> usize

The companion ID of this body.
Source§

fn set_companion_id(&mut self, id: usize)

Set the companion ID of this body (may be reinitialized by nphysics).
Source§

fn ndofs(&self) -> usize

The number of degrees of freedom of this body.
Source§

fn generalized_velocity(&self) -> DVectorSlice<'_, N>

The generalized velocities of this body.
Source§

fn generalized_velocity_mut(&mut self) -> DVectorSliceMut<'_, N>

The mutable generalized velocities of this body.
Source§

fn generalized_acceleration(&self) -> DVectorSlice<'_, N>

The generalized accelerations at each degree of freedom of this body.
Source§

fn integrate(&mut self, parameters: &IntegrationParameters<N>)

Integrate the position of this body.
Source§

fn clear_forces(&mut self)

Reset the timestep-specific dynamic information of this body.
Source§

fn clear_update_flags(&mut self)

Clear all the update flags of this body.
Source§

fn update_kinematics(&mut self)

Updates the kinematics, e.g., positions and jacobians, of this body.
Source§

fn step_started(&mut self)

Source§

fn advance(&mut self, time_ratio: N)

Source§

fn validate_advancement(&mut self)

Source§

fn clamp_advancement(&mut self)

Source§

fn part_motion(&self, _: usize, time_origin: N) -> Option<BodyPartMotion<N>>

Source§

fn update_dynamics(&mut self, dt: N)

Update the dynamics property of this body.
Source§

fn update_acceleration( &mut self, gravity: &Vector<N>, _: &IntegrationParameters<N>, )

Update the acceleration of this body given the forces it is subject to and the gravity.
Source§

fn num_parts(&self) -> usize

The number of parts of this body.
Source§

fn part(&self, i: usize) -> Option<&dyn BodyPart<N>>

A reference to the specified body part.
Source§

fn apply_displacement(&mut self, displacement: &[N])

Applies a generalized displacement to this body.
Source§

fn world_point_at_material_point( &self, _: &dyn BodyPart<N>, point: &Point<N>, ) -> Point<N>

Transform the given point expressed in material coordinates to world-space.
Source§

fn position_at_material_point( &self, _: &dyn BodyPart<N>, point: &Point<N>, ) -> Isometry<N>

Transform the given point expressed in material coordinates to world-space.
Source§

fn material_point_at_world_point( &self, _: &dyn BodyPart<N>, point: &Point<N>, ) -> Point<N>

Transform the given point expressed in material coordinates to world-space.
Source§

fn gravity_enabled(&self) -> bool

Whether this body is affected by gravity.
Source§

fn enable_gravity(&mut self, enabled: bool)

Enable or disable gravity for this body.
Source§

fn velocity_at_point(&self, _: usize, point: &Point<N>) -> Velocity<N>

Gets the velocity of the given point of this body.
Source§

fn fill_constraint_geometry( &self, _: &dyn BodyPart<N>, _: usize, point: &Point<N>, force_dir: &ForceDirection<N>, j_id: usize, wj_id: usize, jacobians: &mut [N], inv_r: &mut N, ext_vels: Option<&DVectorSlice<'_, N>>, out_vel: Option<&mut N>, )

Fills all the jacobians (and the jacobians multiplied by the inverse augmented mass matrix) for a constraint applying a force at the point center (relative to the body part’s center of mass) and the direction dir. Read more
Source§

fn has_active_internal_constraints(&mut self) -> bool

Returns true if this bodies contains internal constraints that need to be solved.
Source§

fn setup_internal_velocity_constraints( &mut self, _: &DVectorSlice<'_, N>, _: &IntegrationParameters<N>, )

Initializes the internal velocity constraints of a body.
Source§

fn warmstart_internal_velocity_constraints( &mut self, _: &mut DVectorSliceMut<'_, N>, )

For warmstarting the solver, modifies the delta velocity applied by the internal constraints of this body.
Source§

fn step_solve_internal_velocity_constraints( &mut self, _: &mut DVectorSliceMut<'_, N>, )

Execute one step for the iterative resolution of this body’s internal velocity constraints.
Source§

fn step_solve_internal_position_constraints( &mut self, _: &IntegrationParameters<N>, )

Execute one step for the iterative resolution of this body’s internal position constraints.
Source§

fn add_local_inertia_and_com( &mut self, _: usize, com: Point<N>, inertia: Inertia<N>, )

Add the given inertia to the local inertia of this body part.
Source§

fn apply_force( &mut self, _: usize, force: &Force<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a force at the center of mass of a part of this body.
Source§

fn apply_local_force( &mut self, _: usize, force: &Force<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a local force at the center of mass of a part of this body.
Source§

fn apply_force_at_point( &mut self, _: usize, force: &Vector<N>, point: &Point<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a force at a given point of a part of this body.
Source§

fn apply_local_force_at_point( &mut self, _: usize, force: &Vector<N>, point: &Point<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a local force at a given point of a part of this body.
Source§

fn apply_force_at_local_point( &mut self, _: usize, force: &Vector<N>, point: &Point<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a force at a given local point of a part of this body.
Source§

fn apply_local_force_at_local_point( &mut self, _: usize, force: &Vector<N>, point: &Point<N>, force_type: ForceType, auto_wake_up: bool, )

Apply a local force at a given local point of a part of this body.
Source§

fn is_ground(&self) -> bool

Returns true if this body is the ground.
Source§

fn update_activation_status(&mut self)

Update whether this body needs to be waken up after a user-interaction.
Source§

fn status_dependent_ndofs(&self) -> usize

The number of degrees of freedom (DOF) of this body, taking its status into account. Read more
Source§

fn status_dependent_body_part_velocity( &self, part: &dyn BodyPart<N>, ) -> Velocity<N>

The velocity of the specified body part, taking this body status into account. Read more
Source§

fn is_active(&self) -> bool

Check if this body is active.
Source§

fn is_dynamic(&self) -> bool

Whether or not the status of this body is dynamic.
Source§

fn is_kinematic(&self) -> bool

Whether or not the status of this body is kinematic.
Source§

fn is_static(&self) -> bool

Whether or not the status of this body is static.
Source§

fn activate(&mut self)

Force the activation of this body.
Source§

impl<N: RealField + Copy> BodyPart<N> for RigidBody<N>

Source§

fn is_ground(&self) -> bool

Returns true if this body part is the ground.
Source§

fn velocity(&self) -> Velocity<N>

The velocity of this body part.
Source§

fn position(&self) -> Isometry<N>

The position of this body part wrt. the ground.
Source§

fn safe_position(&self) -> Isometry<N>

If CCD is enabled, this is the last position known to be tunnelling-free.
Source§

fn local_inertia(&self) -> Inertia<N>

The local-space inertia of this body part.
Source§

fn inertia(&self) -> Inertia<N>

The world-space inertia of this body part.
Source§

fn center_of_mass(&self) -> Point<N>

The center of mass of this body part.
Source§

fn local_center_of_mass(&self) -> Point<N>

The local center of mass of this body part.
Source§

impl<N: Debug + RealField + Copy> Debug for RigidBody<N>

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more

Auto Trait Implementations§

§

impl<N> Freeze for RigidBody<N>
where N: Freeze,

§

impl<N> !RefUnwindSafe for RigidBody<N>

§

impl<N> Send for RigidBody<N>

§

impl<N> Sync for RigidBody<N>

§

impl<N> Unpin for RigidBody<N>
where N: Unpin,

§

impl<N> !UnwindSafe for RigidBody<N>

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> Downcast for T
where T: Any,

Source§

fn into_any(self: Box<T>) -> Box<dyn Any>

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.
Source§

fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>

Convert 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)

Convert &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)

Convert &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
where T: Any + Send + Sync,

Source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Send + Sync>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts 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 more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts 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 more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

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

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.