This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties. More...
#include <src/joint.hpp>

Classes | |
| class | joint_type_exception |
Public Types | |
| enum | JointType { RotAxis, RotX, RotY, RotZ, TransAxis, TransX, TransY, TransZ, None } |
Public Member Functions | |
| 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. | |
| 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 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. | |
| 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 |
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 | |||
| ) |
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 |
References joint_type_ex, RotAxis, TransAxis, and type.
| 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 |
References joint_type_ex, RotAxis, 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, joint_pose, joint_type_ex, KDL::Frame::M, offset, origin, KDL::Frame::p, q_previous, KDL::Rotation::Rot2(), RotAxis, 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, joint_pose, joint_type_ex, KDL::Frame::M, offset, origin, KDL::Frame::p, q_previous, KDL::Rotation::Rot2(), RotAxis, TransAxis, and type.
| KDL::Joint::~Joint | ( | ) | [virtual] |
| const std::string& KDL::Joint::getName | ( | ) | const [inline] |
Request the name of the joint.
References name.
Referenced by KDL::Tree::getChain().
| const JointType& KDL::Joint::getType | ( | ) | const [inline] |
Request the type of the joint.
References type.
Referenced by KDL::Tree::addSegment(), KDL::Chain::addSegment(), KDL::ChainIdSolver_RNE::CartToJnt(), KDL::Tree::getChain(), and KDL::ChainJntToJacSolver::JntToJac().
| const std::string KDL::Joint::getTypeName | ( | ) | const [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().
| 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, KDL::Frame::Identity(), joint_pose, KDL::Frame::M, None, offset, origin, q_previous, KDL::Rotation::Rot2(), RotAxis, KDL::Rotation::RotX(), RotX, KDL::Rotation::RotY(), RotY, KDL::Rotation::RotZ(), RotZ, scale, TransAxis, TransX, TransY, TransZ, and type.
Referenced by KDL::Segment::getFrameToTip(), KDL::Segment::pose(), and KDL::Segment::twist().
| Twist KDL::Joint::twist | ( | const double & | qdot | ) | const |
Vector KDL::Joint::axis [private] |
Referenced by Joint(), JointAxis(), pose(), and twist().
double KDL::Joint::damping [private] |
double KDL::Joint::inertia [private] |
Frame KDL::Joint::joint_pose [mutable, private] |
Referenced by Joint().
std::string KDL::Joint::name [private] |
Referenced by getName().
double KDL::Joint::offset [private] |
Vector KDL::Joint::origin [private] |
Referenced by Joint(), JointOrigin(), and pose().
double KDL::Joint::q_previous [mutable, private] |
double KDL::Joint::scale [private] |
double KDL::Joint::stiffness [private] |
Joint::JointType KDL::Joint::type [private] |
Referenced by getType(), getTypeName(), Joint(), JointAxis(), pose(), and twist().
1.6.3