#[repr(transparent)]pub struct PrismaticJoint {
pub data: GenericJoint,
}Expand description
A sliding joint that allows movement along one axis only (like a piston or sliding door).
Prismatic joints lock all motion except sliding along a single axis. Use for:
- Pistons and hydraulics
- Sliding doors and drawers
- Elevator platforms
- Linear actuators
- Telescoping mechanisms
You can optionally add:
- Limits: Restrict sliding distance (min/max positions)
- Motor: Powered sliding with target velocity or position
The axis is specified when creating the joint and is expressed in each body’s local space.
Fields§
§data: GenericJointThe underlying joint data.
Implementations§
Source§impl PrismaticJoint
impl PrismaticJoint
Sourcepub fn new(axis: UnitVector<f32>) -> Self
pub fn new(axis: UnitVector<f32>) -> Self
Creates a new prismatic joint allowing only relative translations along the specified axis.
This axis is expressed in the local-space of both rigid-bodies.
Sourcepub fn data(&self) -> &GenericJoint
pub fn data(&self) -> &GenericJoint
The underlying generic joint.
Sourcepub fn contacts_enabled(&self) -> bool
pub fn contacts_enabled(&self) -> bool
Are contacts between the attached rigid-bodies enabled?
Sourcepub fn set_contacts_enabled(&mut self, enabled: bool) -> &mut Self
pub fn set_contacts_enabled(&mut self, enabled: bool) -> &mut Self
Sets whether contacts between the attached rigid-bodies are enabled.
Sourcepub fn local_anchor1(&self) -> Point<f32>
pub fn local_anchor1(&self) -> Point<f32>
The joint’s anchor, expressed in the local-space of the first rigid-body.
Sourcepub fn set_local_anchor1(&mut self, anchor1: Point<f32>) -> &mut Self
pub fn set_local_anchor1(&mut self, anchor1: Point<f32>) -> &mut Self
Sets the joint’s anchor, expressed in the local-space of the first rigid-body.
Sourcepub fn local_anchor2(&self) -> Point<f32>
pub fn local_anchor2(&self) -> Point<f32>
The joint’s anchor, expressed in the local-space of the second rigid-body.
Sourcepub fn set_local_anchor2(&mut self, anchor2: Point<f32>) -> &mut Self
pub fn set_local_anchor2(&mut self, anchor2: Point<f32>) -> &mut Self
Sets the joint’s anchor, expressed in the local-space of the second rigid-body.
Sourcepub fn local_axis1(&self) -> UnitVector<f32>
pub fn local_axis1(&self) -> UnitVector<f32>
The principal axis of the joint, expressed in the local-space of the first rigid-body.
Sourcepub fn set_local_axis1(&mut self, axis1: UnitVector<f32>) -> &mut Self
pub fn set_local_axis1(&mut self, axis1: UnitVector<f32>) -> &mut Self
Sets the principal axis of the joint, expressed in the local-space of the first rigid-body.
Sourcepub fn local_axis2(&self) -> UnitVector<f32>
pub fn local_axis2(&self) -> UnitVector<f32>
The principal axis of the joint, expressed in the local-space of the second rigid-body.
Sourcepub fn set_local_axis2(&mut self, axis2: UnitVector<f32>) -> &mut Self
pub fn set_local_axis2(&mut self, axis2: UnitVector<f32>) -> &mut Self
Sets the principal axis of the joint, expressed in the local-space of the second rigid-body.
Sourcepub fn motor(&self) -> Option<&JointMotor>
pub fn motor(&self) -> Option<&JointMotor>
The motor affecting the joint’s translational degree of freedom.
Sourcepub fn set_motor_model(&mut self, model: MotorModel) -> &mut Self
pub fn set_motor_model(&mut self, model: MotorModel) -> &mut Self
Set the spring-like model used by the motor to reach the desired target velocity and position.
Sourcepub fn set_motor_velocity(&mut self, target_vel: f32, factor: f32) -> &mut Self
pub fn set_motor_velocity(&mut self, target_vel: f32, factor: f32) -> &mut Self
Sets the motor’s target sliding speed.
Makes the joint slide at a desired velocity (like a powered piston or conveyor).
§Parameters
target_vel- Desired velocity in units/secondfactor- Motor strength
Sourcepub fn set_motor_position(
&mut self,
target_pos: f32,
stiffness: f32,
damping: f32,
) -> &mut Self
pub fn set_motor_position( &mut self, target_pos: f32, stiffness: f32, damping: f32, ) -> &mut Self
Sets the motor’s target position along the sliding axis.
Makes the joint slide toward a specific position using spring-like behavior.
§Parameters
target_pos- Desired position along the axisstiffness- Spring constantdamping- Resistance to motion
Sourcepub fn set_motor(
&mut self,
target_pos: f32,
target_vel: f32,
stiffness: f32,
damping: f32,
) -> &mut Self
pub fn set_motor( &mut self, target_pos: f32, target_vel: f32, stiffness: f32, damping: f32, ) -> &mut Self
Configures both target position and target velocity for the motor.
Sourcepub fn set_motor_max_force(&mut self, max_force: f32) -> &mut Self
pub fn set_motor_max_force(&mut self, max_force: f32) -> &mut Self
Sets the maximum force the motor can deliver.
Sourcepub fn limits(&self) -> Option<&JointLimits<f32>>
pub fn limits(&self) -> Option<&JointLimits<f32>>
The limit distance attached bodies can translate along the joint’s principal axis.
Sourcepub fn set_limits(&mut self, limits: [f32; 2]) -> &mut Self
pub fn set_limits(&mut self, limits: [f32; 2]) -> &mut Self
Sets the [min,max] limit distances attached bodies can translate along the joint’s principal axis.
Sourcepub fn softness(&self) -> SpringCoefficients<f32>
pub fn softness(&self) -> SpringCoefficients<f32>
Gets the softness of this joint’s locked degrees of freedom.
Sourcepub fn set_softness(&mut self, softness: SpringCoefficients<f32>) -> &mut Self
pub fn set_softness(&mut self, softness: SpringCoefficients<f32>) -> &mut Self
Sets the softness of this joint.
Trait Implementations§
Source§impl Clone for PrismaticJoint
impl Clone for PrismaticJoint
Source§fn clone(&self) -> PrismaticJoint
fn clone(&self) -> PrismaticJoint
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for PrismaticJoint
impl Debug for PrismaticJoint
Source§impl From<PrismaticJoint> for GenericJoint
impl From<PrismaticJoint> for GenericJoint
Source§fn from(val: PrismaticJoint) -> GenericJoint
fn from(val: PrismaticJoint) -> GenericJoint
Source§impl PartialEq for PrismaticJoint
impl PartialEq for PrismaticJoint
impl Copy for PrismaticJoint
impl StructuralPartialEq for PrismaticJoint
Auto Trait Implementations§
impl Freeze for PrismaticJoint
impl RefUnwindSafe for PrismaticJoint
impl Send for PrismaticJoint
impl Sync for PrismaticJoint
impl Unpin for PrismaticJoint
impl UnwindSafe for PrismaticJoint
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>, which can then be
downcast into Box<dyn 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>, which 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> DowncastSend for T
impl<T> DowncastSend for T
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<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.