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, None } |
Public Member Functions | |
const std::string & | getName () const |
const JointType & | getType () 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 |
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 :
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.
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 |
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.
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 |
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.
name | of the joint |
origin | the origin of the joint |
axis | the axis 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 |
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.
origin | the origin of the joint |
axis | the axis 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 |
KDL::Joint::~Joint | ( | ) | [virtual] |
const std::string& KDL::Joint::getName | ( | ) | const [inline] |
const JointType& KDL::Joint::getType | ( | ) | const [inline] |
const std::string KDL::Joint::getTypeName | ( | ) | const [inline] |
Vector KDL::Joint::JointAxis | ( | ) | const |
Vector KDL::Joint::JointOrigin | ( | ) | const |
Frame KDL::Joint::pose | ( | const double & | q | ) | const |
Twist KDL::Joint::twist | ( | const double & | qdot | ) | const |
Vector KDL::Joint::axis [private] |
double KDL::Joint::damping [private] |
double KDL::Joint::inertia [private] |
Frame KDL::Joint::joint_pose [mutable, private] |
std::string KDL::Joint::name [private] |
double KDL::Joint::offset [private] |
Vector KDL::Joint::origin [private] |
double KDL::Joint::q_previous [mutable, private] |
double KDL::Joint::scale [private] |
double KDL::Joint::stiffness [private] |
Joint::JointType KDL::Joint::type [private] |