rapier3d::dynamics

Struct MultibodyJointSet

Source
pub struct MultibodyJointSet { /* private fields */ }
Expand description

A set of rigid bodies that can be handled by a physics pipeline.

Implementations§

Source§

impl MultibodyJointSet

Source

pub fn new() -> Self

Create a new empty set of multibodies.

Source

pub fn iter( &self, ) -> impl Iterator<Item = (MultibodyJointHandle, &MultibodyLinkId, &Multibody, &MultibodyLink)>

Iterates through all the multibody joints from this set.

Source

pub fn insert_kinematic( &mut self, body1: RigidBodyHandle, body2: RigidBodyHandle, data: impl Into<GenericJoint>, wake_up: bool, ) -> Option<MultibodyJointHandle>

Inserts a new kinematic multibody joint into this set.

Source

pub fn insert( &mut self, body1: RigidBodyHandle, body2: RigidBodyHandle, data: impl Into<GenericJoint>, wake_up: bool, ) -> Option<MultibodyJointHandle>

Inserts a new multibody joint into this set.

Source

pub fn remove(&mut self, handle: MultibodyJointHandle, wake_up: bool)

Removes a multibody_joint from this set.

Source

pub fn remove_multibody_articulations( &mut self, handle: RigidBodyHandle, wake_up: bool, )

Removes all the multibody_joints from the multibody the given rigid-body is part of.

Source

pub fn remove_joints_attached_to_rigid_body( &mut self, rb_to_remove: RigidBodyHandle, )

Removes all the multibody joints attached to a rigid-body.

Returns the link of this multibody attached to the given rigid-body.

Returns None if rb isn’t part of any rigid-body.

Source

pub fn get_multibody(&self, index: MultibodyIndex) -> Option<&Multibody>

Gets a reference to a multibody, based on its temporary index.

Source

pub fn get_multibody_mut( &mut self, index: MultibodyIndex, ) -> Option<&mut Multibody>

Gets a mutable reference to a multibody, based on its temporary index. MultibodyJointSet.

Source

pub fn get_multibody_mut_internal( &mut self, index: MultibodyIndex, ) -> Option<&mut Multibody>

Gets a mutable reference to a multibody, based on its temporary index.

This method will bypass any modification-detection automatically done by the MultibodyJointSet.

Source

pub fn get(&self, handle: MultibodyJointHandle) -> Option<(&Multibody, usize)>

Gets a reference to the multibody identified by its handle.

Source

pub fn get_mut( &mut self, handle: MultibodyJointHandle, ) -> Option<(&mut Multibody, usize)>

Gets a mutable reference to the multibody identified by its handle.

Source

pub fn get_mut_internal( &mut self, handle: MultibodyJointHandle, ) -> Option<(&mut Multibody, usize)>

Gets a mutable reference to the multibody identified by its handle.

This method will bypass any modification-detection automatically done by the MultibodyJointSet.

Source

pub fn get_unknown_gen( &self, i: u32, ) -> Option<(&Multibody, usize, MultibodyJointHandle)>

Gets the joint with the given handle without a known generation.

This is useful when you know you want the joint at index i but don’t know what is its current generation number. Generation numbers are used to protect from the ABA problem because the joint position i are recycled between two insertion and a removal.

Using this is discouraged in favor of self.get(handle) which does not suffer form the ABA problem.

Source

pub fn joint_between( &self, rb1: RigidBodyHandle, rb2: RigidBodyHandle, ) -> Option<(MultibodyJointHandle, &Multibody, &MultibodyLink)>

Returns the joint between two rigid-bodies (if it exists).

Source

pub fn attached_joints( &self, rb: RigidBodyHandle, ) -> impl Iterator<Item = (RigidBodyHandle, RigidBodyHandle, MultibodyJointHandle)> + '_

Iterates through all the joints attached to the given rigid-body.

Source

pub fn attached_bodies( &self, body: RigidBodyHandle, ) -> impl Iterator<Item = RigidBodyHandle> + '_

Iterate through the handles of all the rigid-bodies attached to this rigid-body by a multibody_joint.

Source

pub fn bodies_attached_with_enabled_joint( &self, body: RigidBodyHandle, ) -> impl Iterator<Item = RigidBodyHandle> + '_

Iterate through the handles of all the rigid-bodies attached to this rigid-body by an enabled multibody_joint.

Source

pub fn multibodies(&self) -> impl Iterator<Item = &Multibody>

Iterates through all the multibodies on this set.

Trait Implementations§

Source§

impl Clone for MultibodyJointSet

Source§

fn clone(&self) -> MultibodyJointSet

Returns a copy of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for MultibodyJointSet

Source§

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

Formats the value using the given formatter. Read more
Source§

impl Default for MultibodyJointSet

Source§

fn default() -> MultibodyJointSet

Returns the “default value” for a type. Read more
Source§

impl Index<MultibodyIndex> for MultibodyJointSet

Source§

type Output = Multibody

The returned type after indexing.
Source§

fn index(&self, index: MultibodyIndex) -> &Multibody

Performs the indexing (container[index]) operation. Read more

Auto Trait Implementations§

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> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dst: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dst. 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> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. 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> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
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.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V