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

Classes

class  joint_type_exception

Public Types

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

Public Member Functions

const double & getInertia () const
const std::string & getName () const
const JointTypegetType () const
const std::string getTypeName () const
 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)
 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 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

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 
) [explicit]

Constructor of a joint.

Parameters:
nameof the joint
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 27 of file joint.cpp.

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 
) [explicit]

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

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.

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

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

Definition at line 72 of file joint.cpp.


Member Function Documentation

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

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.

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.

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.

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

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

Definition at line 131 of file joint.cpp.

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

Returns:
Vector

Definition at line 157 of file joint.cpp.

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

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


Member Data Documentation

Definition at line 217 of file joint.hpp.

double KDL::Joint::damping [private]

Definition at line 213 of file joint.hpp.

double KDL::Joint::inertia [private]

Definition at line 212 of file joint.hpp.

Frame KDL::Joint::joint_pose [mutable, private]

Definition at line 218 of file joint.hpp.

std::string KDL::Joint::name [private]

Definition at line 208 of file joint.hpp.

double KDL::Joint::offset [private]

Definition at line 211 of file joint.hpp.

Definition at line 217 of file joint.hpp.

double KDL::Joint::q_previous [mutable, private]

Definition at line 219 of file joint.hpp.

double KDL::Joint::scale [private]

Definition at line 210 of file joint.hpp.

double KDL::Joint::stiffness [private]

Definition at line 214 of file joint.hpp.

Definition at line 209 of file joint.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Jun 14 2019 19:33:23