Abstraction of a product of exponentials (POE) formula.
More...
#include <ProductOfExponentials.hpp>
This entity is comprised of a sequence of matrix exponentials and a transformation between the base and the tool frame.
- See also
- MatrixExponential
◆ PoeExpression()
roboticslab::PoeExpression::PoeExpression |
( |
const KDL::Frame & |
H_S_T = KDL::Frame::Identity() | ) |
|
|
inlineexplicit |
- Parameters
-
H_S_T | Transformation between the base and the tool frame. |
◆ append() [1/2]
void roboticslab::PoeExpression::append |
( |
const MatrixExponential & |
exp, |
|
|
const KDL::Frame & |
H_new_old = KDL::Frame::Identity() |
|
) |
| |
|
inline |
All internal coordinates of the input POE term are referred to the current base frame after applying an (optional) intermediate transformation.
- Parameters
-
exp | Input POE term. |
H_new_old | Transformation between the base frame of this POE and the base frame of the input POE term. |
◆ append() [2/2]
void PoeExpression::append |
( |
const PoeExpression & |
poe, |
|
|
const KDL::Frame & |
H_new_old = KDL::Frame::Identity() |
|
) |
| |
All internal coordinates of the input POE are referred to the current base frame after applying an (optional) intermediate transformation. The current tool frame is replaced by the appended POE's tool frame and updated in the same manner.
- Parameters
-
poe | Input POE formula. |
H_new_old | Transformation between the new and the old base frame. |
◆ changeBaseFrame()
void PoeExpression::changeBaseFrame |
( |
const KDL::Frame & |
H_new_old | ) |
|
All POE terms as well as the base-to-tool reference frame will be updated accordingly.
- Parameters
-
H_new_old | Transformation between the new and the old base frame. |
◆ changeToolFrame()
void roboticslab::PoeExpression::changeToolFrame |
( |
const KDL::Frame & |
H_new_old | ) |
|
|
inline |
- Parameters
-
H_new_old | Transformation between the new and the old tool frame. |
◆ evaluate()
bool PoeExpression::evaluate |
( |
const KDL::JntArray & |
q, |
|
|
KDL::Frame & |
H |
|
) |
| const |
- Parameters
-
q | Input joint array (radians). |
H | Output pose in cartesian space. |
- Returns
- False if the size of the input joint array does not match the size of this POE.
◆ exponentialAtJoint()
const MatrixExponential& roboticslab::PoeExpression::exponentialAtJoint |
( |
int |
i | ) |
const |
|
inline |
- Parameters
-
i | Zero-based index of the requested term. |
- Returns
- An unmodifiable reference to said term.
◆ fromChain()
PoeExpression PoeExpression::fromChain |
( |
const KDL::Chain & |
chain | ) |
|
|
static |
- Parameters
-
chain | A KDL kinematic chain representation. |
- Returns
- The resulting POE formula.
- See also
- toChain
◆ getTransform()
const KDL::Frame& roboticslab::PoeExpression::getTransform |
( |
| ) |
const |
|
inline |
- Returns
- Transformation between the base and the tool frame.
◆ makeReverse()
The sequence of POE terms is reversed and the base and tool frames interchanged. Note that theta_i = -theta_(size-i)_reversed.
- Returns
- A reversed copy of this instance.
- See also
- reverseSelf
◆ reverseSelf()
void PoeExpression::reverseSelf |
( |
| ) |
|
The sequence of POE terms is reversed and the base and tool frames interchanged. Note that theta_i = -theta_(size-i)_reversed.
- See also
- makeReverse
◆ size()
int roboticslab::PoeExpression::size |
( |
| ) |
const |
|
inline |
- Returns
- Number of terms in this POE formula.
◆ toChain()
KDL::Chain PoeExpression::toChain |
( |
| ) |
const |
- Returns
- A KDL kinematic chain representation.
- See also
- fromChain
The documentation for this class was generated from the following files: