|
KDL 1.5.3
|
#include <src/joint.hpp>

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 JointType & | getType () const |
| Request the type of the joint. | |
| const std::string | getTypeName () const |
| Request the stringified type of the joint. | |
| const double & | getScale () const |
| Request the scale of the joint. | |
| const double & | getOffset () const |
| Request the offset 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. | |
| const Vector & | getAxis () const |
| Request the axis of the joint. | |
| const Vector & | getOrigin () const |
| Request the origin 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 |
\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 :
|
explicit |
Constructor of a joint.
| name | of the joint |
| type | type of the joint, default: Joint::Fixed |
| 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 |
References damping, inertia, joint_type_ex, name, offset, RotAxis, scale, stiffness, TransAxis, and type.
|
explicit |
Constructor of a joint.
| type | type of the joint, default: Joint::Fixed |
| 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 |
References damping, inertia, joint_type_ex, name, offset, RotAxis, scale, stiffness, TransAxis, and type.
| 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 |
References axis, damping, inertia, joint_type_ex, name, offset, origin, RotAxis, scale, stiffness, TransAxis, and type.
| 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 |
References axis, damping, inertia, joint_type_ex, name, offset, origin, RotAxis, scale, stiffness, TransAxis, and type.
|
virtual |
|
inline |
|
inline |
Request the damping of the joint.
References damping.
|
inline |
Request the inertia of the joint.
References inertia.
Referenced by KDL::TreeIdSolver_RNE::rne_step().
|
inline |
Request the name of the joint.
References name.
Referenced by KDL::Tree::getChain(), and KDL::operator<<().
|
inline |
Request the offset of the joint.
References offset.
|
inline |
Request the origin of the joint.
References origin.
|
inline |
|
inline |
Request the stiffness of the joint.
References stiffness.
|
inline |
Request the type of the joint.
References type.
Referenced by KDL::Chain::addSegment(), KDL::Tree::addSegment(), KDL::ChainIkSolverPos_LMA::compute_fwdpos(), KDL::ChainIkSolverPos_LMA::compute_jacobian(), KDL::Tree::getChain(), KDL::ChainHdSolver_Vereshchagin::initial_upwards_sweep(), and KDL::TreeIdSolver_RNE::rne_step().
|
inline |
| Vector KDL::Joint::JointAxis | ( | ) | const |
| Vector KDL::Joint::JointOrigin | ( | ) | const |
Request the Vector corresponding to the origin of a revolute joint.
References origin.
Referenced by KDL::Tree::getChain(), and KDL::operator<<().
| 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 |
References axis, Fixed, KDL::Frame::Identity(), offset, origin, KDL::Rotation::Rot2(), RotAxis, RotX, KDL::Rotation::RotX(), RotY, KDL::Rotation::RotY(), RotZ, KDL::Rotation::RotZ(), scale, TransAxis, TransX, TransY, TransZ, and type.
| Twist KDL::Joint::twist | ( | const double & | qdot | ) | const |
|
private |
|
private |
Referenced by getDamping(), Joint(), Joint(), Joint(), and Joint().
|
private |
Referenced by getInertia(), Joint(), Joint(), Joint(), and Joint().
|
mutableprivate |
|
private |
|
private |
|
private |
|
private |
Referenced by getOrigin(), Joint(), Joint(), JointOrigin(), and pose().
|
mutableprivate |
|
private |
|
private |
Referenced by getStiffness(), Joint(), Joint(), Joint(), and Joint().
|
private |
Referenced by getType(), getTypeName(), Joint(), Joint(), Joint(), Joint(), JointAxis(), pose(), and twist().