Struct bevy_rapier3d::prelude::MultibodyJoint
source · [−]pub struct MultibodyJoint {
pub data: JointData,
/* private fields */
}
Fields
data: JointData
Implementations
sourceimpl MultibodyJoint
impl MultibodyJoint
pub fn new(data: JointData) -> MultibodyJoint
pub fn local_joint_rot(&self) -> &Unit<Quaternion<f32>>
sourcepub fn body_to_parent(&self) -> Isometry<f32, Unit<Quaternion<f32>>, 3_usize>
pub fn body_to_parent(&self) -> Isometry<f32, Unit<Quaternion<f32>>, 3_usize>
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: &Unit<Quaternion<f32>>,
out: &mut Matrix<f32, Const<{_: usize}>, Dynamic, SliceStorageMut<'_, f32, Const<{_: usize}>, Dynamic, Const<1_usize>, Const<{_: usize}>>>
)
pub fn jacobian(
&self,
transform: &Unit<Quaternion<f32>>,
out: &mut Matrix<f32, Const<{_: usize}>, Dynamic, SliceStorageMut<'_, f32, Const<{_: usize}>, Dynamic, Const<1_usize>, Const<{_: usize}>>>
)
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 Matrix<f32, Dynamic, Const<1_usize>, SliceStorageMut<'_, f32, Dynamic, Const<1_usize>, Const<1_usize>, Dynamic>>
)
pub fn default_damping(
&self,
out: &mut Matrix<f32, Dynamic, Const<1_usize>, SliceStorageMut<'_, f32, Dynamic, Const<1_usize>, Const<1_usize>, Dynamic>>
)
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,
dof_id: usize,
j_id: &mut usize,
jacobians: &mut Matrix<f32, Dynamic, Const<1_usize>, VecStorage<f32, Dynamic, Const<1_usize>>>,
constraints: &mut Vec<AnyJointVelocityConstraint, Global>
)
pub fn velocity_constraints(
&self,
params: &IntegrationParameters,
multibody: &Multibody,
link: &MultibodyLink,
dof_id: usize,
j_id: &mut usize,
jacobians: &mut Matrix<f32, Dynamic, Const<1_usize>, VecStorage<f32, Dynamic, Const<1_usize>>>,
constraints: &mut Vec<AnyJointVelocityConstraint, Global>
)
Initialize and generate velocity constraints to enforce, e.g., multibody_joint limits and motors.
Trait Implementations
sourceimpl Clone for MultibodyJoint
impl Clone for MultibodyJoint
sourcepub fn clone(&self) -> MultibodyJoint
pub fn clone(&self) -> MultibodyJoint
Returns a copy of the value. Read more
1.0.0 · sourcefn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from source
. Read more
sourceimpl Debug for MultibodyJoint
impl Debug for MultibodyJoint
impl Copy for MultibodyJoint
Auto Trait Implementations
impl RefUnwindSafe for MultibodyJoint
impl Send for MultibodyJoint
impl Sync for MultibodyJoint
impl Unpin for MultibodyJoint
impl UnwindSafe for MultibodyJoint
Blanket Implementations
sourceimpl<T> BorrowMut<T> for T where
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
const: unstable · sourcepub fn borrow_mut(&mut self) -> &mut T
pub fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
impl<T> Downcast for T where
T: Any,
impl<T> Downcast for T where
T: Any,
pub fn into_any(self: Box<T, Global>) -> Box<dyn Any + 'static, Global>
pub 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
pub fn into_any_rc(self: Rc<T>) -> Rc<dyn Any + 'static>
pub 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
pub fn as_any(&self) -> &(dyn Any + 'static)
pub 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
pub fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)
pub 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> Instrument for T
impl<T> Instrument for T
sourcefn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
sourcefn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
impl<T> Pointable for T
impl<T> Pointable for T
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub 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.
sourcepub fn to_owned(&self) -> T
pub fn to_owned(&self) -> T
Creates owned data from borrowed data, usually by cloning. Read more
sourcepub fn clone_into(&self, target: &mut T)
pub fn clone_into(&self, target: &mut T)
toowned_clone_into
)Uses borrowed data to replace owned data, usually by cloning. Read more
impl<T> TypeData for T where
T: 'static + Send + Sync + Clone,
impl<T> TypeData for T where
T: 'static + Send + Sync + Clone,
pub fn clone_type_data(&self) -> Box<dyn TypeData + 'static, Global>
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
pub fn vzip(self) -> V
sourceimpl<T> WithSubscriber for T
impl<T> WithSubscriber for T
sourcefn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self> where
S: Into<Dispatch>,
fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self> where
S: Into<Dispatch>,
Attaches the provided Subscriber
to this type, returning a
WithDispatch
wrapper. Read more
sourcefn with_current_subscriber(self) -> WithDispatch<Self>
fn with_current_subscriber(self) -> WithDispatch<Self>
Attaches the current default Subscriber
to this type, returning a
WithDispatch
wrapper. Read more