pub struct Joint {
pub joint_type: JointType,
pub parent_to_joint: SpatialTransform,
pub axis: Vec3,
pub damping: f64,
pub limits: Option<[f64; 2]>,
}Expand description
A joint connecting two bodies.
Fields§
§joint_type: JointTypeJoint type.
parent_to_joint: SpatialTransformTransform from parent body frame to joint frame (constant).
axis: Vec3Joint axis in local frame (for revolute: typically Z).
damping: f64Damping coefficient.
limits: Option<[f64; 2]>Joint position limits [lower, upper] (None = unlimited).
Implementations§
Source§impl Joint
impl Joint
Sourcepub fn revolute(parent_to_joint: SpatialTransform) -> Self
pub fn revolute(parent_to_joint: SpatialTransform) -> Self
Create a revolute joint with the given parent-to-joint transform.
Sourcepub fn prismatic(parent_to_joint: SpatialTransform, axis: Vec3) -> Self
pub fn prismatic(parent_to_joint: SpatialTransform, axis: Vec3) -> Self
Create a prismatic joint with the given parent-to-joint transform and axis.
Sourcepub fn spherical(parent_to_joint: SpatialTransform) -> Self
pub fn spherical(parent_to_joint: SpatialTransform) -> Self
Create a spherical (ball) joint with the given parent-to-joint transform.
Sourcepub fn free(parent_to_joint: SpatialTransform) -> Self
pub fn free(parent_to_joint: SpatialTransform) -> Self
Create a free joint with the given parent-to-joint transform.
Sourcepub fn fixed(parent_to_joint: SpatialTransform) -> Self
pub fn fixed(parent_to_joint: SpatialTransform) -> Self
Create a fixed joint (rigid attachment).
Sourcepub fn joint_transform_slice(&self, q: &[f64]) -> SpatialTransform
pub fn joint_transform_slice(&self, q: &[f64]) -> SpatialTransform
Compute the joint transform for the given joint position(s).
Returns the Plücker transform from predecessor to successor frame.
q slice should have length >= ndof().
Sourcepub fn joint_transform(&self, q: f64) -> SpatialTransform
pub fn joint_transform(&self, q: f64) -> SpatialTransform
Compute the joint transform for a single-DOF joint (backward compat). For multi-DOF joints, use joint_transform_slice instead.
Sourcepub fn motion_subspace_matrix(&self) -> DMat
pub fn motion_subspace_matrix(&self) -> DMat
Motion subspace matrix S for this joint. Returns a matrix of size 6 × ndof. For single-DOF joints, returns a 6×1 column vector.
Sourcepub fn motion_subspace(&self) -> SpatialVec
pub fn motion_subspace(&self) -> SpatialVec
Motion subspace for single-DOF joints (backward compat). For multi-DOF joints, use motion_subspace_matrix instead. Fixed joints return a zero vector.
Trait Implementations§
Auto Trait Implementations§
impl Freeze for Joint
impl RefUnwindSafe for Joint
impl Send for Joint
impl Sync for Joint
impl Unpin for Joint
impl UnsafeUnpin for Joint
impl UnwindSafe for Joint
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<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.