pub struct MultibodyJoint {
pub data: GenericJoint,
pub kinematic: bool,
/* private fields */
}
Expand description
An joint attached to two bodies based on the reduced coordinates formalism.
Fields§
§data: GenericJoint
The joint’s description.
kinematic: bool
Is the joint a kinematic joint?
Kinematic joint velocities are never changed by the physics engine. This gives the user total control over the values of their degrees of freedoms.
Implementations§
Source§impl MultibodyJoint
impl MultibodyJoint
Sourcepub fn new(data: GenericJoint, kinematic: bool) -> Self
pub fn new(data: GenericJoint, kinematic: bool) -> Self
Creates a new multibody joint from its description.
Sourcepub fn body_to_parent(&self) -> Isometry<f32>
pub fn body_to_parent(&self) -> Isometry<f32>
The position of the multibody link containing this multibody_joint relative to its parent.
Sourcepub fn integrate(&mut self, dt: f32, vels: &[f32])
pub fn integrate(&mut self, dt: f32, vels: &[f32])
Integrate the position of this multibody_joint.
Sourcepub fn apply_displacement(&mut self, disp: &[f32])
pub fn apply_displacement(&mut self, disp: &[f32])
Apply a displacement to the multibody_joint.
Sourcepub fn jacobian(
&self,
transform: &Rotation<f32>,
out: &mut JacobianViewMut<'_, f32>,
)
pub fn jacobian( &self, transform: &Rotation<f32>, out: &mut JacobianViewMut<'_, f32>, )
Sets in out
the non-zero entries of the multibody_joint jacobian transformed by transform
.
Sourcepub fn jacobian_mul_coordinates(&self, acc: &[f32]) -> RigidBodyVelocity
pub fn jacobian_mul_coordinates(&self, acc: &[f32]) -> RigidBodyVelocity
Multiply the multibody_joint jacobian by generalized velocities to obtain the relative velocity of the multibody link containing this multibody_joint.
Sourcepub fn default_damping(&self, out: &mut DVectorViewMut<'_, f32>)
pub fn default_damping(&self, out: &mut DVectorViewMut<'_, f32>)
Fill out
with the non-zero entries of a damping that can be applied by default to ensure a good stability of the multibody_joint.
Sourcepub fn num_velocity_constraints(&self) -> usize
pub fn num_velocity_constraints(&self) -> usize
Maximum number of velocity constrains that can be generated by this multibody_joint.
Sourcepub fn velocity_constraints(
&self,
params: &IntegrationParameters,
multibody: &Multibody,
link: &MultibodyLink,
j_id: usize,
jacobians: &mut DVector<f32>,
constraints: &mut [JointGenericOneBodyConstraint],
) -> usize
pub fn velocity_constraints( &self, params: &IntegrationParameters, multibody: &Multibody, link: &MultibodyLink, j_id: usize, jacobians: &mut DVector<f32>, constraints: &mut [JointGenericOneBodyConstraint], ) -> usize
Initialize and generate velocity constraints to enforce, e.g., multibody_joint limits and motors.
Trait Implementations§
Source§impl Clone for MultibodyJoint
impl Clone for MultibodyJoint
Source§fn clone(&self) -> MultibodyJoint
fn clone(&self) -> MultibodyJoint
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for MultibodyJoint
impl Debug for MultibodyJoint
impl Copy for MultibodyJoint
Auto Trait Implementations§
impl Freeze for MultibodyJoint
impl RefUnwindSafe for MultibodyJoint
impl Send for MultibodyJoint
impl Sync for MultibodyJoint
impl Unpin for MultibodyJoint
impl UnwindSafe for MultibodyJoint
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.