pub struct JointModelPrismatic {
pub axis: SpatialMotion,
pub limits: JointLimits,
pub bias: SpatialMotion,
}Expand description
Model of a prismatic joint.
This joint constraints two objects to translate along a given axis.
Fields§
§axis: SpatialMotionThe axis of translation expressed in the local frame of the joint.
limits: JointLimitsThe joint limits.
bias: SpatialMotionThe (null) bias of the joint.
Implementations§
Source§impl JointModelPrismatic
impl JointModelPrismatic
Sourcepub fn new(axis: Vector3D) -> Self
pub fn new(axis: Vector3D) -> Self
Creates a new JointModelPrismatic with the given axis of translation and unbounded limits.
The axis of translation should be normalized and expressed in the local frame of the joint.
§Arguments
axis- The normalized axis of translation expressed in the local frame of the joint.
§Returns
A new JointModelPrismatic object.
Sourcepub fn new_px() -> Self
pub fn new_px() -> Self
Creates a new prismatic joint model with x as axis of translation.
§Returns
A new JointModelPrismatic object.
Trait Implementations§
Source§impl Clone for JointModelPrismatic
impl Clone for JointModelPrismatic
Source§fn clone(&self) -> JointModelPrismatic
fn clone(&self) -> JointModelPrismatic
Returns a duplicate of the value. Read more
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source. Read moreSource§impl Debug for JointModelPrismatic
impl Debug for JointModelPrismatic
Source§impl Display for JointModelPrismatic
impl Display for JointModelPrismatic
Source§impl JointModel for JointModelPrismatic
impl JointModel for JointModelPrismatic
Source§fn get_joint_type(&self) -> JointType
fn get_joint_type(&self) -> JointType
Returns the joint type.
Source§fn neutral(&self) -> Configuration
fn neutral(&self) -> Configuration
Returns the neutral configuration of the joint.
Source§fn create_joint_data(&self) -> JointDataWrapper
fn create_joint_data(&self) -> JointDataWrapper
Creates the joint data.
Source§fn get_axis(&self) -> &SpatialMotion
fn get_axis(&self) -> &SpatialMotion
Returns the axis of the joint, if applicable.
Source§fn random_configuration(&self, rng: &mut ThreadRng) -> Configuration
fn random_configuration(&self, rng: &mut ThreadRng) -> Configuration
Returns a random configuration for the joint.
Source§fn subspace(&self, v: &Configuration) -> SpatialMotion
fn subspace(&self, v: &Configuration) -> SpatialMotion
Applies the joint subspace constraint to obtain the motion associated with a given velocity configuration.
Source§fn subspace_dual(&self, f: &SpatialForce) -> Configuration
fn subspace_dual(&self, f: &SpatialForce) -> Configuration
Applies the dual of the joint subspace constraint to obtain the force/torque associated with a given spatial force.
Source§fn subspace_se3(&self, se3: &SE3) -> SpatialMotion
fn subspace_se3(&self, se3: &SE3) -> SpatialMotion
Applies the joint subspace constraint to a given SE3 transformation, returning the resulting spatial motion.
Source§fn bias(&self) -> &SpatialMotion
fn bias(&self) -> &SpatialMotion
Returns the joint bias (Coriolis and centrifugal effects).
Source§fn integrate(&self, q: &Configuration, v: &Configuration) -> Configuration
fn integrate(&self, q: &Configuration, v: &Configuration) -> Configuration
Integrates the joint configuration given the current configuration and velocity.
Auto Trait Implementations§
impl Freeze for JointModelPrismatic
impl RefUnwindSafe for JointModelPrismatic
impl Send for JointModelPrismatic
impl Sync for JointModelPrismatic
impl Unpin for JointModelPrismatic
impl UnsafeUnpin for JointModelPrismatic
impl UnwindSafe for JointModelPrismatic
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
Mutably borrows from an owned value. Read more
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
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>
The inverse inclusion map: attempts to construct
self from the equivalent element of its
superset. Read moreSource§fn 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).Source§fn 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.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self to the equivalent element of its superset.