rapier2d::dynamics

Struct Multibody

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

An articulated body simulated using the reduced-coordinates approach.

Implementations§

Source§

impl Multibody

Source

pub fn new() -> Self

Creates a new multibody with no link.

Source

pub fn self_contacts_enabled(&self) -> bool

Whether self-contacts are enabled on this multibody.

If set to false no two link from this multibody can generate contacts, even if the contact is enabled on the individual joint with GenericJoint::contacts_enabled.

Source

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

Sets whether self-contacts are enabled on this multibody.

If set to false no two link from this multibody can generate contacts, even if the contact is enabled on the individual joint with GenericJoint::contacts_enabled.

Source

pub fn inv_augmented_mass(&self) -> &LU<f32, Dyn, Dyn>

The inverse augmented mass matrix of this multibody.

Source

pub fn root(&self) -> &MultibodyLink

The first link of this multibody.

Source

pub fn root_mut(&mut self) -> &mut MultibodyLink

Mutable reference to the first link of this multibody.

Reference i-th multibody link of this multibody.

Return None if there is less than i + 1 multibody links.

Mutable reference to the multibody link with the given id.

Return None if the given id does not identifies a multibody link part of self.

The number of links on this multibody.

Iterator through all the links of this multibody.

All link are guaranteed to be yielded before its descendant.

Mutable iterator through all the links of this multibody.

All link are guaranteed to be yielded before its descendant.

Source

pub fn damping(&self) -> &DVector<f32>

The vector of damping applied to this multibody.

Source

pub fn damping_mut(&mut self) -> &mut DVector<f32>

Mutable vector of damping applied to this multibody.

Source

pub fn joint_velocity(&self, link: &MultibodyLink) -> DVectorView<'_, f32>

The generalized velocity at the multibody_joint of the given link.

Source

pub fn generalized_acceleration(&self) -> DVectorView<'_, f32>

The generalized accelerations of this multibodies.

Source

pub fn generalized_velocity(&self) -> DVectorView<'_, f32>

The generalized velocities of this multibodies.

Source

pub fn body_jacobian(&self, link_id: usize) -> &Jacobian<f32>

The body jacobian for link link_id calculated by the last call to Multibody::forward_kinematics.

Source

pub fn generalized_velocity_mut(&mut self) -> DVectorViewMut<'_, f32>

The mutable generalized velocities of this multibodies.

Source

pub fn apply_displacements(&mut self, disp: &[f32])

Apply displacements, in generalized coordinates, to this multibody.

Note this does not updates the link poses, only their generalized coordinates. To update the link poses and associated rigid-bodies, call Self::forward_kinematics.

Source

pub fn update_rigid_bodies( &self, bodies: &mut RigidBodySet, update_mass_properties: bool, )

Update the rigid-body poses based on this multibody joint poses.

This is typically called after Self::forward_kinematics to apply the new joint poses to the rigid-bodies.

Source

pub fn forward_kinematics( &mut self, bodies: &RigidBodySet, read_root_pose_from_rigid_body: bool, )

Apply forward-kinematics to this multibody.

This will update the MultibodyLink pose information as wall as the body jacobians. This will also ensure that the multibody has the proper number of degrees of freedom if its root node changed between dynamic and non-dynamic.

Note that this does not update the poses of the RigidBody attached to the joints. Run Self::update_rigid_bodies to trigger that update.

This method updates self with the result of the forward-kinematics operation. For a non-mutable version running forward kinematics on a single link, see Self::forward_kinematics_single_link.

§Parameters
  • bodies: the set of rigid-bodies.
  • read_root_pose_from_rigid_body: if set to true, the root joint (either a fixed joint, or a free joint) will have its pose set to its associated-rigid-body pose. Set this to true when the root rigid-body pose has been modified and needs to affect the multibody.
Source

pub fn kinematic_branch(&self, link_id: usize) -> Vec<usize>

Computes the ids of all the links between the root and the link identified by link_id.

Apply forward-kinematics to compute the position of a single link of this multibody.

If out_jacobian is Some, this will simultaneously compute the new jacobian of this link. If displacement is Some, the generalized position considered during transform propagation is the sum of the current position of self and this displacement.

Source

pub fn forward_kinematics_single_branch( &self, bodies: &RigidBodySet, branch: &[usize], displacement: Option<&[f32]>, out_jacobian: Option<&mut Jacobian<f32>>, ) -> Isometry<f32>

Apply forward-kinematics to compute the position of a single sorted branch of this multibody.

The given branch must have the following properties:

  • It must be sorted, i.e., branch[i] < branch[i + 1].
  • All the indices must be part of the same kinematic branch.
  • If a link is branch[i], then branch[i - 1] must be its parent.

In general, this method shouldn’t be used directly and [Self::forward_kinematics_single_link̦] should be preferred since it computes the branch indices automatically.

If you want to calculate the branch indices manually, see Self::kinematic_branch.

If out_jacobian is Some, this will simultaneously compute the new jacobian of this branch. This represents the body jacobian for the last link in the branch.

If displacement is Some, the generalized position considered during transform propagation is the sum of the current position of self and this displacement.

Source

pub fn ndofs(&self) -> usize

The total number of freedoms of this multibody.

Source§

impl Multibody

Source

pub fn inverse_kinematics_delta( &self, link_id: usize, desired_movement: &SpacialVector<f32>, damping: f32, displacements: &mut DVector<f32>, )

Computes the displacement needed to have the link identified by link_id move by the desired transform.

The displacement calculated by this function is added to the displacement vector.

Source

pub fn inverse_kinematics_delta_with_jacobian( jacobian: &Jacobian<f32>, desired_movement: &SpacialVector<f32>, damping: f32, displacements: &mut DVector<f32>, )

Computes the displacement needed to have a link with the given jacobian move by the desired transform.

The displacement calculated by this function is added to the displacement vector.

Source

pub fn inverse_kinematics( &self, bodies: &RigidBodySet, link_id: usize, options: &InverseKinematicsOption, target_pose: &Isometry<f32>, joint_can_move: impl Fn(&MultibodyLink) -> bool, displacements: &mut DVector<f32>, )

Computes the displacement needed to have the link identified by link_id have a pose equal (or as close as possible) to target_pose.

If displacement is given non-zero, the current pose of the rigid-body is considered to be obtained from its current generalized coordinates summed with the displacement vector.

The displacements vector is overwritten with the new displacement.

The joint_can_move argument is a closure that lets you indicate which joint can be moved through the inverse-kinematics process. Any joint for which joint_can_move returns false will have its corresponding displacement constrained to 0. Set the closure to |_| true if all the joints are free to move.

Trait Implementations§

Source§

impl Clone for Multibody

Source§

fn clone(&self) -> Multibody

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 Multibody

Source§

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

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

impl Default for Multibody

Source§

fn default() -> Self

Returns the “default value” for a type. 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