Enum JointType

Source
pub enum JointType {
    Fixed,
    Revolute,
    Continuous,
    Prismatic,
    Floating,
    Planar,
}
Expand description

An enum to represent the the types of Joint.

Currently, only URDF types are listed.

It is important to note that multi-axis jointtypes, like Floating and Planar, are often incompatible with lots of different tooling for ROS/URDF, like sensor_msgs/JointState messages from for example joint_state_publisher which has chosen to ignore it. This is a result of most programs (like kdl_parser and joint_state_publisher) only supporting single axis joints. Gazebo/SDFormat supports multi-access joints, but do not have an Floating or Planar equivalent. However, these JointTypes (Mostly Planar) can be approximated by a combination of other joints.

The sections cited from the URDF specification are accurate as of 2023-08-21.

Variants§

§

Fixed

A Fixed joint.

The URDF Specification says the following:

fixed — this is not really a joint because it cannot move. All degrees of freedom are locked. This type of joint does not require the <axis>, <calibration>, <dynamics>, <limits> or <safety_controller>.

§

Revolute

A Revolute joint. (A limited rotational joint, like a weld)

This joint rotates a limited range around a specified (or default) axis.

The URDF Specification says the following:

revolute — a hinge joint that rotates along the axis and has a limited range specified by the upper and lower limits.

§

Continuous

A Continuous rotational joint. (A bearing or motor connection, like a wheel)

This joint rotates around a specified (or default) axis.

Since this Jointtype is unlimited in its movement, the Limit should not be specified (??TODO: effort and velocity migth be useable??).

The URDF Specification says the following:

continuous — a continuous hinge joint that rotates around the axis and has no upper and lower limits.

§

Prismatic

A Prismitic joint. (A limited sliding joint, like a drawer rail or a linear actuator)

This joint slides a limited range along a specified (or default) axis.

The URDF Specification says the following:

prismatic — a sliding joint that slides along the axis, and has a limited range specified by the upper and lower limits.

§

Floating

A Floating joint. (Or a non-connection)

This is a joint to represent an unconnected link. Most parsers do not handle this JointType, since it’s not an actual joint and it causes problems with lots of different tooling for ROS/URDF, like sensor_msgs/JointState messages from for example joint_state_publisher which has chosen to ignore it.

The URDF Specification says the following:

floating — this joint allows motion for all 6 degrees of freedom.

§

Planar

A Planar joint. (A plane contact, like a magnet on a metal sheet)

This joint slides on the plane perpendicular the specified (or default) axis. This JointType might cause problems with lots of different tooling for ROS/URDF, like sensor_msgs/JointState messages from for example joint_state_publisher which has chosen to ignore it.

The URDF Specification says the following:

planar — this joint allows motion in a plane perpendicular to the axis.

Trait Implementations§

Source§

impl Clone for JointType

Source§

fn clone(&self) -> JointType

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for JointType

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Default for JointType

Source§

fn default() -> JointType

Returns the “default value” for a type. Read more
Source§

impl From<JointType> for Cow<'_, [u8]>

Source§

fn from(value: JointType) -> Self

Converts to this type from the input type.
Source§

impl PartialEq for JointType

Source§

fn eq(&self, other: &JointType) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl ToString for JointType

Source§

fn to_string(&self) -> String

Converts the given value to a String. Read more
Source§

impl Copy for JointType

Source§

impl Eq for JointType

Source§

impl StructuralPartialEq for JointType

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts 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 more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts 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 more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

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

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,