Blender  V3.3
Public Types | Public Member Functions | List of all members
KDL::Joint Class Reference

This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties. More...

#include <joint.hpp>

Public Types

enum  JointType {
  RotX , RotY , RotZ , TransX ,
  TransY , TransZ , Sphere , Swing ,
  None
}
 

Public Member Functions

 Joint (const JointType &type=None, const double &scale=1, const double &offset=0, const double &inertia=0, const double &damping=0, const double &stiffness=0)
 
 Joint (const Joint &in)
 
Jointoperator= (const Joint &arg)
 
Frame pose (const double *q) const
 
Twist twist (const double &qdot, int dof=0) const
 
const JointTypegetType () const
 
const std::string getTypeName () const
 
unsigned int getNDof () const
 
virtual ~Joint ()
 

Detailed Description

This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties.

A simple joint is described by the following properties :

Definition at line 43 of file joint.hpp.

Member Enumeration Documentation

◆ JointType

Enumerator
RotX 
RotY 
RotZ 
TransX 
TransY 
TransZ 
Sphere 
Swing 
None 

Definition at line 45 of file joint.hpp.

Constructor & Destructor Documentation

◆ Joint() [1/2]

KDL::Joint::Joint ( const JointType type = None,
const double scale = 1,
const double offset = 0,
const double inertia = 0,
const double damping = 0,
const double stiffness = 0 
)

Constructor of a joint.

Parameters
typetype of the joint, default: Joint::None
scalescale between joint input and actual geometric movement, default: 1
offsetoffset between joint input and actual geometric input, default: 0
inertia1D inertia along the joint axis, default: 0
damping1D damping along the joint axis, default: 0
stiffness1D stiffness along the joint axis, default: 0

Definition at line 29 of file joint.cpp.

◆ Joint() [2/2]

KDL::Joint::Joint ( const Joint in)

Definition at line 36 of file joint.cpp.

◆ ~Joint()

KDL::Joint::~Joint ( )
virtual

Definition at line 54 of file joint.cpp.

Member Function Documentation

◆ getNDof()

unsigned int KDL::Joint::getNDof ( ) const

◆ getType()

const JointType& KDL::Joint::getType ( ) const
inline

Request the type of the joint.

Returns
const reference to the type

Definition at line 88 of file joint.hpp.

Referenced by iTaSC::Armature::addLimitConstraint(), iTaSC::Armature::addSegment(), base_callback(), and execute_scene().

◆ getTypeName()

const std::string KDL::Joint::getTypeName ( ) const
inline

Request the stringified type of the joint.

Returns
const string

Definition at line 98 of file joint.hpp.

References None, RotX, RotY, RotZ, Sphere, Swing, TransX, TransY, and TransZ.

Referenced by KDL::operator<<().

◆ operator=()

Joint & KDL::Joint::operator= ( const Joint arg)

Definition at line 42 of file joint.cpp.

◆ pose()

Frame KDL::Joint::pose ( const double q) const

Request the 6D-pose between the beginning and the end of the joint at joint position q

Parameters
qthe 1D joint position
Returns
the resulting 6D-pose

Definition at line 58 of file joint.cpp.

References KDL::Frame::Identity(), Rot(), KDL::Rotation::RotX(), RotX, KDL::Rotation::RotY(), RotY, KDL::Rotation::RotZ(), RotZ, Sphere, Swing, TransX, TransY, and TransZ.

Referenced by KDL::Segment::pose().

◆ twist()

Twist KDL::Joint::twist ( const double qdot,
int  dof = 0 
) const

Request the resulting 6D-velocity with a joint velocity qdot

Parameters
qdotthe 1D joint velocity
Returns
the resulting 6D-velocity

Definition at line 104 of file joint.cpp.

References RotX, RotY, RotZ, Sphere, Swing, TransX, TransY, TransZ, and KDL::Twist::Zero().

Referenced by KDL::Segment::twist().


The documentation for this class was generated from the following files: