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>

List of all members.

Public Types

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

Public Member Functions

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.
 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.
 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 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.
 Joint (const std::string &name, 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.
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.
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.
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 45 of file joint.hpp.


Member Enumeration Documentation

Enumerator:
RotAxis 
RotX 
RotY 
RotZ 
TransAxis 
TransX 
TransY 
TransZ 
None 

Definition at line 47 of file joint.hpp.


Constructor & Destructor Documentation

KDL::Joint::Joint ( const std::string &  name,
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:
name of the joint
type type of the joint, default: Joint::None
scale scale between joint input and actual geometric movement, default: 1
offset offset between joint input and actual geometric input, default: 0
inertia 1D inertia along the joint axis, default: 0
damping 1D damping along the joint axis, default: 0
stiffness 1D stiffness along the joint axis, default: 0

Definition at line 27 of file joint.cpp.

References RotAxis, and TransAxis.

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:
type type of the joint, default: Joint::None
scale scale between joint input and actual geometric movement, default: 1
offset offset between joint input and actual geometric input, default: 0
inertia 1D inertia along the joint axis, default: 0
damping 1D damping along the joint axis, default: 0
stiffness 1D stiffness along the joint axis, default: 0

Definition at line 35 of file joint.cpp.

References RotAxis, and TransAxis.

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:
name of the joint
_origin the origin of the joint
_axis the axis of the joint
type type of the joint
_scale scale between joint input and actual geometric movement, default: 1
_offset offset between joint input and actual geometric input, default: 0
_inertia 1D inertia along the joint axis, default: 0
_damping 1D damping along the joint axis, default: 0
_stiffness 1D stiffness along the joint axis, default: 0

Definition at line 43 of file joint.cpp.

References KDL::Frame::M, KDL::Frame::p, KDL::Rotation::Rot2(), RotAxis, and TransAxis.

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:
_origin the origin of the joint
_axis the axis of the joint
type type of the joint
_scale scale between joint input and actual geometric movement, default: 1
_offset offset between joint input and actual geometric input, default: 0
_inertia 1D inertia along the joint axis, default: 0
_damping 1D damping along the joint axis, default: 0
_stiffness 1D stiffness along the joint axis, default: 0

Definition at line 56 of file joint.cpp.

References KDL::Frame::M, KDL::Frame::p, KDL::Rotation::Rot2(), RotAxis, and TransAxis.

KDL::Joint::~Joint (  )  [virtual]

Definition at line 68 of file joint.cpp.


Member Function Documentation

const std::string& KDL::Joint::getName ( void   )  const [inline]

Request the name of the joint.

Returns:
const reference to the name of the joint

Definition at line 152 of file joint.hpp.

Referenced by KDL::Tree::getChain().

const JointType& KDL::Joint::getType ( void   )  const [inline]
const std::string KDL::Joint::getTypeName ( void   )  const [inline]

Request the stringified type of the joint.

Returns:
const string

Definition at line 171 of file joint.hpp.

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

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 144 of file joint.cpp.

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

Referenced by KDL::Tree::getChain().

Vector KDL::Joint::JointOrigin (  )  const

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

Returns:
Vector

Definition at line 178 of file joint.cpp.

Referenced by KDL::Tree::getChain().

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:
q the 1D joint position
Returns:
the resulting 6D-pose

Definition at line 72 of file joint.cpp.

References KDL::Frame::Identity(), KDL::Frame::M, None, KDL::Rotation::Rot2(), RotAxis, KDL::Rotation::RotX(), RotX, KDL::Rotation::RotY(), RotY, KDL::Rotation::RotZ(), RotZ, TransAxis, TransX, TransY, and TransZ.

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

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

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

Parameters:
qdot the 1D joint velocity
Returns:
the resulting 6D-velocity

Definition at line 111 of file joint.cpp.

References None, RotAxis, RotX, RotY, RotZ, TransAxis, TransX, TransY, TransZ, and KDL::Twist::Zero().

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


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

Generated on Wed Nov 23 19:02:18 2011 for FreeCAD by  doxygen 1.6.1