KDL 1.5.1
Loading...
Searching...
No Matches
Classes | Public Types | Public Member Functions | Private Attributes | List of all members
KDL::Joint Class Reference

#include <src/joint.hpp>

Collaboration diagram for KDL::Joint:
Collaboration graph
[legend]

Classes

class  joint_type_exception
 

Public Types

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

Public Member Functions

 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)
 Constructor of a 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)
 Constructor of a 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.
 
 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.
 
Frame pose (const double &q) const
 Request the 6D-pose between the beginning and the end of the joint at joint position q.
 
Twist twist (const double &qdot) const
 Request the resulting 6D-velocity with a joint velocity qdot.
 
Vector JointAxis () const
 Request the Vector corresponding to the axis of a revolute joint.
 
Vector JointOrigin () const
 Request the Vector corresponding to the origin of a revolute joint.
 
const std::string & getName () const
 Request the name of the joint.
 
const JointTypegetType () const
 Request the type of the joint.
 
const std::string getTypeName () const
 Request the stringified type of the joint.
 
const double & getInertia () const
 Request the inertia of the joint.
 
const double & getDamping () const
 Request the damping of the joint.
 
const double & getStiffness () const
 Request the stiffness of the joint.
 
virtual ~Joint ()
 

Private Attributes

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

Detailed Description

 \brief 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 :

Member Enumeration Documentation

◆ JointType

Enumerator
RotAxis 
RotX 
RotY 
RotZ 
TransAxis 
TransX 
TransY 
TransZ 
Fixed 
None 

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

References joint_type_ex, q_previous, RotAxis, TransAxis, and type.

◆ 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

References joint_type_ex, q_previous, RotAxis, TransAxis, and type.

◆ 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

References axis, joint_pose, joint_type_ex, KDL::Frame::M, offset, origin, KDL::Frame::p, q_previous, KDL::Rotation::Rot2(), RotAxis, TransAxis, and type.

◆ 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

References axis, joint_pose, joint_type_ex, KDL::Frame::M, offset, origin, KDL::Frame::p, q_previous, KDL::Rotation::Rot2(), RotAxis, TransAxis, and type.

◆ ~Joint()

KDL::Joint::~Joint ( )
virtual

Member Function Documentation

◆ getDamping()

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

Request the damping of the joint.

Returns
const reference to the damping of the joint

References damping.

◆ getInertia()

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

Request the inertia of the joint.

Returns
const reference to the inertia of the joint

References inertia.

Referenced by KDL::ChainIdSolver_RNE::CartToJnt(), KDL::ChainHdSolver_Vereshchagin::downwards_sweep(), KDL::ChainDynParam::JntToMass(), and KDL::TreeIdSolver_RNE::rne_step().

◆ getName()

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

Request the name of the joint.

Returns
const reference to the name of the joint

References name.

Referenced by KDL::Tree::getChain(), and KDL::operator<<().

◆ getStiffness()

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

Request the stiffness of the joint.

Returns
const reference to the stiffness of the joint

References stiffness.

◆ getType()

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

◆ getTypeName()

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

Request the stringified type of the joint.

Returns
const string

References Fixed, RotAxis, RotX, RotY, RotZ, TransAxis, TransX, TransY, TransZ, and type.

Referenced by KDL::operator<<().

◆ 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.

References axis, Fixed, RotAxis, RotX, RotY, RotZ, TransAxis, TransX, TransY, TransZ, type, and KDL::Vector::Zero().

Referenced by KDL::Tree::getChain(), and KDL::operator<<().

◆ JointOrigin()

Vector KDL::Joint::JointOrigin ( ) const

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

Returns
Vector

References origin.

Referenced by KDL::Tree::getChain(), and KDL::operator<<().

◆ 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

References axis, Fixed, KDL::Frame::Identity(), joint_pose, KDL::Frame::M, offset, origin, q_previous, KDL::Rotation::Rot2(), RotAxis, KDL::Rotation::RotX(), RotX, KDL::Rotation::RotY(), RotY, KDL::Rotation::RotZ(), RotZ, scale, TransAxis, TransX, TransY, TransZ, and type.

Referenced by KDL::Segment::getFrameToTip(), KDL::Segment::pose(), KDL::Segment::setFrameToTip(), and KDL::Segment::twist().

◆ 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

References axis, Fixed, RotAxis, RotX, RotY, RotZ, scale, TransAxis, TransX, TransY, TransZ, type, and KDL::Twist::Zero().

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

Member Data Documentation

◆ axis

Vector KDL::Joint::axis
private

Referenced by Joint(), JointAxis(), pose(), and twist().

◆ damping

double KDL::Joint::damping
private

Referenced by getDamping().

◆ inertia

double KDL::Joint::inertia
private

Referenced by getInertia().

◆ joint_pose

Frame KDL::Joint::joint_pose
mutableprivate

Referenced by Joint(), and pose().

◆ joint_type_ex

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

Referenced by Joint().

◆ name

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

Referenced by getName().

◆ offset

double KDL::Joint::offset
private

Referenced by Joint(), and pose().

◆ origin

Vector KDL::Joint::origin
private

Referenced by Joint(), JointOrigin(), and pose().

◆ q_previous

double KDL::Joint::q_previous
mutableprivate

Referenced by Joint(), and pose().

◆ scale

double KDL::Joint::scale
private

Referenced by pose(), and twist().

◆ stiffness

double KDL::Joint::stiffness
private

Referenced by getStiffness().

◆ type

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

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