This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties. More...
#include <joint.hpp>
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 JointType & | getType () 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 () |
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.
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.
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 | |||
) |
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 | |
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.
_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.
const std::string& KDL::Joint::getName | ( | void | ) | const [inline] |
Request 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] |
Request the type of the joint.
Definition at line 161 of file joint.hpp.
Referenced by KDL::Tree::addSegment(), KDL::Chain::addSegment(), KDL::ChainIdSolver_RNE::CartToJnt(), KDL::Tree::getChain(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::ChainDynParam::JntToMass().
const std::string KDL::Joint::getTypeName | ( | void | ) | const [inline] |
Vector KDL::Joint::JointAxis | ( | ) | const |
Vector KDL::Joint::JointOrigin | ( | ) | const |
Request the Vector corresponding to the origin of a revolute joint.
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.
q | the 1D joint position |
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.
qdot | the 1D joint 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().