pub struct Multibody { /* private fields */ }
Expand description
An articulated body simulated using the reduced-coordinates approach.
Implementations§
Source§impl Multibody
impl Multibody
Sourcepub fn self_contacts_enabled(&self) -> bool
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
.
Sourcepub fn set_self_contacts_enabled(&mut self, enabled: bool)
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
.
Sourcepub fn inv_augmented_mass(&self) -> &LU<f32, Dyn, Dyn>
pub fn inv_augmented_mass(&self) -> &LU<f32, Dyn, Dyn>
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<f32>
pub fn damping_mut(&mut self) -> &mut DVector<f32>
Mutable vector of damping applied to this multibody.
Sourcepub fn joint_velocity(&self, link: &MultibodyLink) -> DVectorView<'_, f32>
pub fn joint_velocity(&self, link: &MultibodyLink) -> DVectorView<'_, f32>
The generalized velocity at the multibody_joint of the given link.
Sourcepub fn generalized_acceleration(&self) -> DVectorView<'_, f32>
pub fn generalized_acceleration(&self) -> DVectorView<'_, f32>
The generalized accelerations of this multibodies.
Sourcepub fn generalized_velocity(&self) -> DVectorView<'_, f32>
pub fn generalized_velocity(&self) -> DVectorView<'_, f32>
The generalized velocities of this multibodies.
Sourcepub fn body_jacobian(&self, link_id: usize) -> &Jacobian<f32>
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
.
Sourcepub fn generalized_velocity_mut(&mut self) -> DVectorViewMut<'_, f32>
pub fn generalized_velocity_mut(&mut self) -> DVectorViewMut<'_, f32>
The mutable generalized velocities of this multibodies.
Sourcepub fn apply_displacements(&mut self, disp: &[f32])
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
.
Sourcepub fn update_rigid_bodies(
&self,
bodies: &mut RigidBodySet,
update_mass_properties: bool,
)
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.
Sourcepub fn forward_kinematics(
&mut self,
bodies: &RigidBodySet,
read_root_pose_from_rigid_body: bool,
)
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 totrue
, the root joint (either a fixed joint, or a free joint) will have its pose set to its associated-rigid-body pose. Set this totrue
when the root rigid-body pose has been modified and needs to affect the multibody.
Sourcepub fn kinematic_branch(&self, link_id: usize) -> Vec<usize>
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
.
Sourcepub fn forward_kinematics_single_link(
&self,
bodies: &RigidBodySet,
link_id: usize,
displacement: Option<&[f32]>,
out_jacobian: Option<&mut Jacobian<f32>>,
) -> Isometry<f32>
pub fn forward_kinematics_single_link( &self, bodies: &RigidBodySet, link_id: usize, displacement: Option<&[f32]>, out_jacobian: Option<&mut Jacobian<f32>>, ) -> Isometry<f32>
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
.
Sourcepub fn forward_kinematics_single_branch(
&self,
bodies: &RigidBodySet,
branch: &[usize],
displacement: Option<&[f32]>,
out_jacobian: Option<&mut Jacobian<f32>>,
) -> Isometry<f32>
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]
, thenbranch[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§impl Multibody
impl Multibody
Sourcepub fn inverse_kinematics_delta(
&self,
link_id: usize,
desired_movement: &SpacialVector<f32>,
damping: f32,
displacements: &mut DVector<f32>,
)
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.
Sourcepub fn inverse_kinematics_delta_with_jacobian(
jacobian: &Jacobian<f32>,
desired_movement: &SpacialVector<f32>,
damping: f32,
displacements: &mut DVector<f32>,
)
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.
Sourcepub 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>,
)
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§
Auto Trait Implementations§
impl Freeze for Multibody
impl RefUnwindSafe for Multibody
impl Send for Multibody
impl Sync for Multibody
impl Unpin for Multibody
impl UnwindSafe for Multibody
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> Downcast for Twhere
T: Any,
impl<T> Downcast for Twhere
T: Any,
Source§fn into_any(self: Box<T>) -> Box<dyn Any>
fn into_any(self: Box<T>) -> Box<dyn Any>
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>
fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>
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)
fn as_any(&self) -> &(dyn Any + 'static)
&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)
fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
&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
impl<T> DowncastSync for T
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
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 moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
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 moreSource§impl<T> Pointable for T
impl<T> Pointable for T
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.