This class encapsulates a simple joint, that is with one parameterized degree of freedom and with scalar dynamic properties.
More...
#include <joint.hpp>
List of all members.
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 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 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 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 JointType &type=None, 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 |
Detailed Description
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.
Definition at line 45 of file joint.hpp.
Member Enumeration Documentation
- Enumerator:
RotAxis |
|
RotX |
|
RotY |
|
RotZ |
|
TransAxis |
|
TransX |
|
TransY |
|
TransZ |
|
None |
|
Definition at line 47 of file joint.hpp.
Constructor & Destructor Documentation
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.
- Parameters:
-
| 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 |
Definition at line 27 of file joint.cpp.
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.
- Parameters:
-
| 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 |
Definition at line 35 of file joint.cpp.
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 |
Definition at line 43 of file joint.cpp.
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 |
Definition at line 56 of file joint.cpp.
KDL::Joint::~Joint |
( |
|
) |
[virtual] |
Member Function Documentation
const std::string& KDL::Joint::getName |
( |
|
) |
const [inline] |
Request the name of the joint
- Returns:
- const reference to the name of the joint
Definition at line 150 of file joint.hpp.
const JointType& KDL::Joint::getType |
( |
|
) |
const [inline] |
Request the type of the joint.
- Returns:
- const reference to the type
Definition at line 159 of file joint.hpp.
const std::string KDL::Joint::getTypeName |
( |
|
) |
const [inline] |
Request the stringified type of the joint.
- Returns:
- const string
Definition at line 169 of file joint.hpp.
Vector KDL::Joint::JointAxis |
( |
|
) |
const |
Request the Vector corresponding to the axis of a revolute joint.
- Returns:
- Vector. e.g (1,0,0) for RotX etc.
Definition at line 144 of file joint.cpp.
Vector KDL::Joint::JointOrigin |
( |
|
) |
const |
Request the Vector corresponding to the origin of a revolute joint.
- Returns:
- Vector
Definition at line 178 of file joint.cpp.
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
Definition at line 72 of file joint.cpp.
Twist KDL::Joint::twist |
( |
const double & |
qdot |
) |
const |
Request the resulting 6D-velocity with a joint velocity qdot
- Parameters:
-
| qdot | the 1D joint velocity |
- Returns:
- the resulting 6D-velocity
Definition at line 111 of file joint.cpp.
Member Data Documentation
The documentation for this class was generated from the following files: