pub struct RevoluteJoint<N: RealField + Copy> { /* private fields */ }Expand description
A unit joint that allows only one relative rotational degree of freedom between two multibody links.
Implementations§
Source§impl<N: RealField + Copy> RevoluteJoint<N>
impl<N: RealField + Copy> RevoluteJoint<N>
Sourcepub fn axis(&self) -> Unit<AngularVector<N>>
pub fn axis(&self) -> Unit<AngularVector<N>>
The axis of the rotational degree of freedom.
Sourcepub fn rotation(&self) -> &Rotation<N>
pub fn rotation(&self) -> &Rotation<N>
The rotation from an attached multibody link to its dependent.
Sourcepub fn local_jacobian(&self) -> &Velocity<N>
pub fn local_jacobian(&self) -> &Velocity<N>
The jacobian of this joint expressed in the local coordinate frame of the joint.
Sourcepub fn local_jacobian_dot(&self) -> &Velocity<N>
pub fn local_jacobian_dot(&self) -> &Velocity<N>
The time-derivative of the jacobian of this joint expressed in the local coordinate frame of the joint.
Sourcepub fn local_jacobian_dot_veldiff(&self) -> &Velocity<N>
pub fn local_jacobian_dot_veldiff(&self) -> &Velocity<N>
The velocity-derivative of the time-derivative of the jacobian of this joint expressed in the local coordinate frame of the joint.
Sourcepub fn disable_min_angle(&mut self)
pub fn disable_min_angle(&mut self)
Disable the lower limit of the rotation angle.
Sourcepub fn disable_max_angle(&mut self)
pub fn disable_max_angle(&mut self)
Disable the upper limit of the rotation angle.
Sourcepub fn enable_min_angle(&mut self, limit: N)
pub fn enable_min_angle(&mut self, limit: N)
Enable and set the lower limit of the rotation angle.
Sourcepub fn enable_max_angle(&mut self, limit: N)
pub fn enable_max_angle(&mut self, limit: N)
Enable and set the upper limit of the rotation angle.
Sourcepub fn is_angular_motor_enabled(&self) -> bool
pub fn is_angular_motor_enabled(&self) -> bool
Return true if the angular motor of this joint is enabled.
Sourcepub fn enable_angular_motor(&mut self)
pub fn enable_angular_motor(&mut self)
Enable the angular motor of this joint.
Sourcepub fn disable_angular_motor(&mut self)
pub fn disable_angular_motor(&mut self)
Disable the angular motor of this joint.
Sourcepub fn desired_angular_motor_velocity(&self) -> N
pub fn desired_angular_motor_velocity(&self) -> N
The desired angular velocity of the joint motor.
Sourcepub fn set_desired_angular_motor_velocity(&mut self, vel: N)
pub fn set_desired_angular_motor_velocity(&mut self, vel: N)
Set the desired angular velocity of the joint motor.
Sourcepub fn max_angular_motor_velocity(&self) -> N
pub fn max_angular_motor_velocity(&self) -> N
The max angular velocity that the joint motor will attempt.
Sourcepub fn set_max_angular_motor_velocity(&mut self, max_vel: N)
pub fn set_max_angular_motor_velocity(&mut self, max_vel: N)
Set the maximum angular velocity that the joint motor will attempt.
Sourcepub fn max_angular_motor_torque(&self) -> N
pub fn max_angular_motor_torque(&self) -> N
The maximum torque that can be delivered by the joint motor.
Sourcepub fn set_max_angular_motor_torque(&mut self, torque: N)
pub fn set_max_angular_motor_torque(&mut self, torque: N)
Set the maximum torque that can be delivered by the joint motor.
Trait Implementations§
Source§impl<N: Clone + RealField + Copy> Clone for RevoluteJoint<N>
impl<N: Clone + RealField + Copy> Clone for RevoluteJoint<N>
Source§fn clone(&self) -> RevoluteJoint<N>
fn clone(&self) -> RevoluteJoint<N>
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl<N: RealField + Copy> Joint<N> for RevoluteJoint<N>
impl<N: RealField + Copy> Joint<N> for RevoluteJoint<N>
Source§fn body_to_parent(
&self,
parent_shift: &Vector<N>,
body_shift: &Vector<N>,
) -> Isometry<N>
fn body_to_parent( &self, parent_shift: &Vector<N>, body_shift: &Vector<N>, ) -> Isometry<N>
Source§fn update_jacobians(&mut self, body_shift: &Vector<N>, vels: &[N])
fn update_jacobians(&mut self, body_shift: &Vector<N>, vels: &[N])
Source§fn jacobian(&self, transform: &Isometry<N>, out: &mut JacobianSliceMut<'_, N>)
fn jacobian(&self, transform: &Isometry<N>, out: &mut JacobianSliceMut<'_, N>)
out the non-zero entries of the joint jacobian transformed by transform.Source§fn jacobian_dot(
&self,
transform: &Isometry<N>,
out: &mut JacobianSliceMut<'_, N>,
)
fn jacobian_dot( &self, transform: &Isometry<N>, out: &mut JacobianSliceMut<'_, N>, )
out the non-zero entries of the time-derivative of the joint jacobian transformed by transform.Source§fn jacobian_dot_veldiff_mul_coordinates(
&self,
transform: &Isometry<N>,
acc: &[N],
out: &mut JacobianSliceMut<'_, N>,
)
fn jacobian_dot_veldiff_mul_coordinates( &self, transform: &Isometry<N>, acc: &[N], out: &mut JacobianSliceMut<'_, N>, )
out the non-zero entries of the velocity-derivative of the time-derivative of the joint jacobian transformed by transform.Source§fn integrate(&mut self, parameters: &IntegrationParameters<N>, vels: &[N])
fn integrate(&mut self, parameters: &IntegrationParameters<N>, vels: &[N])
Source§fn default_damping(&self, out: &mut DVectorSliceMut<'_, N>)
fn default_damping(&self, out: &mut DVectorSliceMut<'_, N>)
out with the non-zero entries of a damping that can be applied by default to ensure a good stability of the joint.Source§fn apply_displacement(&mut self, disp: &[N])
fn apply_displacement(&mut self, disp: &[N])
Source§fn jacobian_mul_coordinates(&self, acc: &[N]) -> Velocity<N>
fn jacobian_mul_coordinates(&self, acc: &[N]) -> Velocity<N>
Source§fn jacobian_dot_mul_coordinates(&self, acc: &[N]) -> Velocity<N>
fn jacobian_dot_mul_coordinates(&self, acc: &[N]) -> Velocity<N>
fn clone(&self) -> Box<dyn Joint<N>>
Source§fn num_velocity_constraints(&self) -> usize
fn num_velocity_constraints(&self) -> usize
Source§fn velocity_constraints(
&self,
parameters: &IntegrationParameters<N>,
multibody: &Multibody<N>,
link: &MultibodyLink<N>,
assembly_id: usize,
dof_id: usize,
ext_vels: &[N],
ground_j_id: &mut usize,
jacobians: &mut [N],
constraints: &mut ConstraintSet<N, (), (), usize>,
)
fn velocity_constraints( &self, parameters: &IntegrationParameters<N>, multibody: &Multibody<N>, link: &MultibodyLink<N>, assembly_id: usize, dof_id: usize, ext_vels: &[N], ground_j_id: &mut usize, jacobians: &mut [N], constraints: &mut ConstraintSet<N, (), (), usize>, )
Source§fn num_position_constraints(&self) -> usize
fn num_position_constraints(&self) -> usize
Source§fn position_constraint(
&self,
_: usize,
multibody: &Multibody<N>,
link: &MultibodyLink<N>,
handle: BodyPartHandle<()>,
dof_id: usize,
jacobians: &mut [N],
) -> Option<GenericNonlinearConstraint<N, ()>>
fn position_constraint( &self, _: usize, multibody: &Multibody<N>, link: &MultibodyLink<N>, handle: BodyPartHandle<()>, dof_id: usize, jacobians: &mut [N], ) -> Option<GenericNonlinearConstraint<N, ()>>
Source§impl<N: RealField + Copy> UnitJoint<N> for RevoluteJoint<N>
impl<N: RealField + Copy> UnitJoint<N> for RevoluteJoint<N>
Source§fn motor(&self) -> &JointMotor<N, N>
fn motor(&self) -> &JointMotor<N, N>
Source§fn min_position(&self) -> Option<N>
fn min_position(&self) -> Option<N>
Source§fn max_position(&self) -> Option<N>
fn max_position(&self) -> Option<N>
impl<N: Copy + RealField + Copy> Copy for RevoluteJoint<N>
Auto Trait Implementations§
impl<N> Freeze for RevoluteJoint<N>where
N: Freeze,
impl<N> RefUnwindSafe for RevoluteJoint<N>where
N: RefUnwindSafe,
impl<N> Send for RevoluteJoint<N>
impl<N> Sync for RevoluteJoint<N>
impl<N> Unpin for RevoluteJoint<N>where
N: Unpin,
impl<N> UnwindSafe for RevoluteJoint<N>where
N: UnwindSafe,
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<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.