pub struct Multibody { /* private fields */ }
Expand description
An articulated body simulated using the reduced-coordinates approach.
Implementations
sourceimpl Multibody
impl Multibody
sourcepub fn inv_augmented_mass(&self) -> &LU<Real, Dynamic, Dynamic>
pub fn inv_augmented_mass(&self) -> &LU<Real, Dynamic, Dynamic>
The inverse augmented mass matrix of this multibody.
sourcepub fn root(&self) -> &MultibodyLink
pub fn root(&self) -> &MultibodyLink
The first link of this multibody.
sourcepub fn root_mut(&mut self) -> &mut MultibodyLink
pub fn root_mut(&mut self) -> &mut MultibodyLink
Mutable reference to the first link of this multibody.
sourcepub fn link(&self, id: usize) -> Option<&MultibodyLink>
pub fn link(&self, id: usize) -> Option<&MultibodyLink>
Reference i
-th multibody link of this multibody.
Return None
if there is less than i + 1
multibody links.
sourcepub fn link_mut(&mut self, id: usize) -> Option<&mut MultibodyLink>
pub fn link_mut(&mut self, id: usize) -> Option<&mut MultibodyLink>
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
.
sourcepub fn links(&self) -> impl Iterator<Item = &MultibodyLink>
pub fn links(&self) -> impl Iterator<Item = &MultibodyLink>
Iterator through all the links of this multibody.
All link are guaranteed to be yielded before its descendant.
sourcepub fn links_mut(&mut self) -> impl Iterator<Item = &mut MultibodyLink>
pub fn links_mut(&mut self) -> impl Iterator<Item = &mut MultibodyLink>
Mutable iterator through all the links of this multibody.
All link are guaranteed to be yielded before its descendant.
sourcepub fn damping_mut(&mut self) -> &mut DVector<Real>
pub fn damping_mut(&mut self) -> &mut DVector<Real>
Mutable vector of damping applied to this multibody.
sourcepub fn generalized_acceleration(&self) -> DVectorSlice<'_, Real>
pub fn generalized_acceleration(&self) -> DVectorSlice<'_, Real>
The generalized accelerations of this multibodies.
sourcepub fn generalized_velocity(&self) -> DVectorSlice<'_, Real>
pub fn generalized_velocity(&self) -> DVectorSlice<'_, Real>
The generalized velocities of this multibodies.
sourcepub fn generalized_velocity_mut(&mut self) -> DVectorSliceMut<'_, Real>
pub fn generalized_velocity_mut(&mut self) -> DVectorSliceMut<'_, Real>
The mutable generalized velocities of this multibodies.
sourcepub fn apply_displacements(&mut self, disp: &[Real])
pub fn apply_displacements(&mut self, disp: &[Real])
Apply displacements, in generalized coordinates, to this multibody.
sourcepub fn forward_kinematics(
&mut self,
bodies: &mut RigidBodySet,
update_mass_props: bool
)
pub fn forward_kinematics(
&mut self,
bodies: &mut RigidBodySet,
update_mass_props: bool
)
Apply forward-kinematics to this multibody and its related rigid-bodies.
Trait Implementations
Auto Trait Implementations
impl RefUnwindSafe for Multibody
impl Send for Multibody
impl Sync for Multibody
impl Unpin for Multibody
impl UnwindSafe for Multibody
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