Struct arcos_kdl::joint::Joint [−][src]
pub struct Joint { /* fields omitted */ }
Expand description
Defines a robotic Joint
joint_type: JointType
that defines the type of the joint
scale: received cmd
mut moves cmd*scale
units
offset: received cmd
mut moves cmd+offset
inertia: Meassurement of inertia for Dynamic purposes
damping: Used for Impedance control
stiffness: Used for Impedance control
axis: Rotational or translational axis of this joint
Implementations
Returns the default Joint, of type NoJoint
, no scale, offset
or any Dynamic parameter.
Create a new Joint with the given Type, and sets the appropiate axis
Create a new Joint with the given offset
Create a new Joint with the given inertial parameter
Create a new Joint with the given damping parameter
Create a new Joint with the given stiffness parameter
Returns the type of this Joint
Calculates the pose of the Joint, given its current state
Calculates the velocity of the Joint, given its current joint-speed
Get the action-axis of this Joint
Trait Implementations
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error> where
__D: Deserializer<'de>,
fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error> where
__D: Deserializer<'de>,
Deserialize this value from the given Serde deserializer. Read more
Auto Trait Implementations
impl RefUnwindSafe for Joint
impl UnwindSafe for Joint
Blanket Implementations
Mutably borrows from an owned value. Read more
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
pub fn is_in_subset(&self) -> bool
pub fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
pub fn to_subset_unchecked(&self) -> SS
pub fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
pub fn from_subset(element: &SS) -> SP
pub fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.