|
| | 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 & | 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.
|
| |
| virtual | ~Joint () |
| |
\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 :
- scale: ratio between motion input and motion output
- offset: between the "physical" and the "logical" zero position.
- type: revolute or translational, along one of the basic frame axes
- inertia, stiffness and damping: scalars representing the physical effects along/about the joint axis only.
| 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
-
| 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_pose, joint_type_ex, name, offset, origin, q_previous, KDL::Rotation::Rot2(), 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.
- Parameters
-
| 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_pose, joint_type_ex, name, offset, origin, q_previous, KDL::Rotation::Rot2(), RotAxis, scale, stiffness, TransAxis, and type.
| 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
-
- Returns
- the resulting 6D-pose
References axis, Fixed, KDL::Frame::Identity(), joint_pose, offset, origin, q_previous, KDL::Rotation::Rot2(), RotAxis, RotX, KDL::Rotation::RotX(), RotY, KDL::Rotation::RotY(), RotZ, KDL::Rotation::RotZ(), scale, TransAxis, TransX, TransY, TransZ, and type.