Abstraction of a term in a product of exponentials (POE) formula.
More...
#include <MatrixExponential.hpp>
|
motion | motionType |
|
KDL::Vector | axis |
|
KDL::Vector | origin |
|
◆ motion
Enumerator |
---|
ROTATION | Revolute joint (zero-pitch twist).
|
TRANSLATION | Prismatic joint (infinite-pitch twist).
|
◆ MatrixExponential()
MatrixExponential::MatrixExponential |
( |
motion |
motionType, |
|
|
const KDL::Vector & |
axis, |
|
|
const KDL::Vector & |
origin = KDL::Vector::Zero() |
|
) |
| |
- Parameters
-
motionType | Screw motion type as defined in motion. |
axis | Screw axis. |
origin | A point along the screw axis (defaults to (0, 0, 0), ignored in prismatic joints). |
◆ asFrame()
KDL::Frame MatrixExponential::asFrame |
( |
double |
theta | ) |
const |
- Parameters
-
theta | Input magnitude this screw should be computed at. |
- Returns
- Resulting homogeneous transformation matrix.
◆ changeBase()
void MatrixExponential::changeBase |
( |
const KDL::Frame & |
H_new_old | ) |
|
- Parameters
-
H_new_old | Transformation between the new and the old base frame. |
- See also
- cloneWithBase
◆ cloneWithBase()
MatrixExponential MatrixExponential::cloneWithBase |
( |
const KDL::Frame & |
H_new_old | ) |
const |
- Parameters
-
H_new_old | Transformation between the new and the old base frame. |
- Returns
- An instance referred to the new frame.
- See also
- changeBase
◆ getAxis()
const KDL::Vector& roboticslab::MatrixExponential::getAxis |
( |
| ) |
const |
|
inline |
- Returns
- A vector representing the direction of the screw axis.
◆ getMotionType()
motion roboticslab::MatrixExponential::getMotionType |
( |
| ) |
const |
|
inline |
- Returns
- A motion type this term has been registered with.
◆ getOrigin()
const KDL::Vector& roboticslab::MatrixExponential::getOrigin |
( |
| ) |
const |
|
inline |
- Returns
- A vector representing the position of some point along the screw axis.
The documentation for this class was generated from the following files: