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 JointType
s (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 PartialEq for JointType
impl PartialEq for JointType
impl Copy for JointType
impl Eq for JointType
impl StructuralEq for JointType
impl StructuralPartialEq for JointType
Auto Trait Implementations§
impl RefUnwindSafe for JointType
impl Send for JointType
impl Sync for JointType
impl Unpin for JointType
impl UnwindSafe for JointType
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
§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read more§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).§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.