Classes | Public Types | Public Member Functions | Private Attributes | 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>

Classes

class  joint_type_exception
 

Public Types

enum  JointType {
  RotAxis, RotX, RotY, RotZ,
  TransAxis, TransX, TransY, TransZ,
  Fixed, None =Fixed
}
 

Public Member Functions

const VectorgetAxis () const
 
const double & getDamping () const
 
const double & getInertia () const
 
const std::string & getName () const
 
const double & getOffset () const
 
const VectorgetOrigin () const
 
const double & getScale () const
 
const double & getStiffness () const
 
const JointTypegetType () const
 
const std::string getTypeName () const
 
 Joint (const std::string &name, const JointType &type=Fixed, const double &scale=1, const double &offset=0, const double &inertia=0, const double &damping=0, const double &stiffness=0)
 
 Joint (const JointType &type=Fixed, const double &scale=1, const double &offset=0, const double &inertia=0, const double &damping=0, const double &stiffness=0)
 
 Joint (const std::string &name, const Vector &_origin, const Vector &_axis, const JointType &type, const double &_scale=1, const double &_offset=0, const double &_inertia=0, const double &_damping=0, const double &_stiffness=0)
 
 Joint (const Vector &_origin, const Vector &_axis, const JointType &type, const double &_scale=1, const double &_offset=0, const double &_inertia=0, const double &_damping=0, const double &_stiffness=0)
 
Vector JointAxis () const
 
Vector JointOrigin () const
 
Frame pose (const double &q) const
 
Twist twist (const double &qdot) const
 
virtual ~Joint ()
 

Private Attributes

Vector axis
 
double damping
 
double inertia
 
Frame joint_pose
 
KDL::Joint::joint_type_exception joint_type_ex
 
std::string name
 
double offset
 
Vector origin
 
double q_previous
 
double scale
 
double stiffness
 
Joint::JointType type
 

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 45 of file joint.hpp.

Member Enumeration Documentation

◆ JointType

Enumerator
RotAxis 
RotX 
RotY 
RotZ 
TransAxis 
TransX 
TransY 
TransZ 
Fixed 
None 

Definition at line 47 of file joint.hpp.

Constructor & Destructor Documentation

◆ Joint() [1/4]

KDL::Joint::Joint ( const std::string &  name,
const JointType type = Fixed,
const double &  scale = 1,
const double &  offset = 0,
const double &  inertia = 0,
const double &  damping = 0,
const double &  stiffness = 0 
)
explicit

Constructor of a joint.

Parameters
nameof the joint
typetype of the joint, default: Joint::Fixed
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 27 of file joint.cpp.

◆ Joint() [2/4]

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

Constructor of a joint.

Parameters
typetype of the joint, default: Joint::Fixed
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 36 of file joint.cpp.

◆ Joint() [3/4]

KDL::Joint::Joint ( const std::string &  name,
const Vector _origin,
const Vector _axis,
const JointType type,
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
nameof the joint
originthe origin of the joint
axisthe axis of the joint
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 45 of file joint.cpp.

◆ Joint() [4/4]

KDL::Joint::Joint ( const Vector _origin,
const Vector _axis,
const JointType type,
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
originthe origin of the joint
axisthe axis of the joint
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 55 of file joint.cpp.

◆ ~Joint()

KDL::Joint::~Joint ( )
virtual

Definition at line 64 of file joint.cpp.

Member Function Documentation

◆ getAxis()

const Vector& KDL::Joint::getAxis ( ) const
inline

Request the axis of the joint.

Returns
const reference to the axis of the joint

Definition at line 250 of file joint.hpp.

◆ getDamping()

const double& KDL::Joint::getDamping ( ) const
inline

Request the damping of the joint.

Returns
const reference to the damping of the joint

Definition at line 230 of file joint.hpp.

◆ getInertia()

const double& KDL::Joint::getInertia ( ) const
inline

Request the inertia of the joint.

Returns
const reference to the inertia of the joint

Definition at line 220 of file joint.hpp.

◆ getName()

const std::string& KDL::Joint::getName ( ) const
inline

Request the name of the joint

Returns
const reference to the name of the joint

Definition at line 150 of file joint.hpp.

◆ getOffset()

const double& KDL::Joint::getOffset ( ) const
inline

Request the offset of the joint.

Returns
const reference to the offset of the joint

Definition at line 210 of file joint.hpp.

◆ getOrigin()

const Vector& KDL::Joint::getOrigin ( ) const
inline

Request the origin of the joint.

Returns
const reference to the origin of the joint

Definition at line 260 of file joint.hpp.

◆ getScale()

const double& KDL::Joint::getScale ( ) const
inline

Request the scale of the joint.

Returns
const reference to the scale of the joint

Definition at line 200 of file joint.hpp.

◆ getStiffness()

const double& KDL::Joint::getStiffness ( ) const
inline

Request the stiffness of the joint.

Returns
const reference to the stiffness of the joint

Definition at line 240 of file joint.hpp.

◆ getType()

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

Request the type of the joint.

Returns
const reference to the type

Definition at line 159 of file joint.hpp.

◆ getTypeName()

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

Request the stringified type of the joint.

Returns
const string

Definition at line 169 of file joint.hpp.

◆ JointAxis()

Vector KDL::Joint::JointAxis ( ) const

Request the Vector corresponding to the axis of a revolute joint.

Returns
Vector. e.g (1,0,0) for RotX etc.

Definition at line 118 of file joint.cpp.

◆ JointOrigin()

Vector KDL::Joint::JointOrigin ( ) const

Request the Vector corresponding to the origin of a revolute joint.

Returns
Vector

Definition at line 144 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 68 of file joint.cpp.

◆ twist()

Twist KDL::Joint::twist ( const double &  qdot) const

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

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

Definition at line 93 of file joint.cpp.

Member Data Documentation

◆ axis

Vector KDL::Joint::axis
private

Definition at line 277 of file joint.hpp.

◆ damping

double KDL::Joint::damping
private

Definition at line 273 of file joint.hpp.

◆ inertia

double KDL::Joint::inertia
private

Definition at line 272 of file joint.hpp.

◆ joint_pose

Frame KDL::Joint::joint_pose
mutableprivate

Definition at line 278 of file joint.hpp.

◆ joint_type_ex

KDL::Joint::joint_type_exception KDL::Joint::joint_type_ex
private

◆ name

std::string KDL::Joint::name
private

Definition at line 268 of file joint.hpp.

◆ offset

double KDL::Joint::offset
private

Definition at line 271 of file joint.hpp.

◆ origin

Vector KDL::Joint::origin
private

Definition at line 277 of file joint.hpp.

◆ q_previous

double KDL::Joint::q_previous
mutableprivate

Definition at line 279 of file joint.hpp.

◆ scale

double KDL::Joint::scale
private

Definition at line 270 of file joint.hpp.

◆ stiffness

double KDL::Joint::stiffness
private

Definition at line 274 of file joint.hpp.

◆ type

Joint::JointType KDL::Joint::type
private

Definition at line 269 of file joint.hpp.


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


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:15