FK solver using Screw Theory.
More...
#include <ChainFkSolverPos_ST.hpp>
|
int | JntToCart (const KDL::JntArray &q_in, KDL::Frame &p_out, int segmentNr=-1) override |
| Perform FK on the selected segment. More...
|
|
int | JntToCart (const KDL::JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1) override |
| Perform FK on the selected segments (unsupported) More...
|
|
void | updateInternalDataStructures () override |
| Update the internal data structures. More...
|
|
const char * | strError (const int error) const override |
| Return a description of the last error. More...
|
|
|
| ChainFkSolverPos_ST (const KDL::Chain &chain) |
|
Implementation of a forward position kinematics algorithm. This is a thin wrapper around PoeExpression. Methods that retrieve resulting frames for intermediate links are not supported.
◆ create()
KDL::ChainFkSolverPos * ChainFkSolverPos_ST::create |
( |
const KDL::Chain & |
chain | ) |
|
|
static |
- Parameters
-
chain | Input kinematic chain. |
- Returns
- Solver instance.
◆ JntToCart() [1/2]
int ChainFkSolverPos_ST::JntToCart |
( |
const KDL::JntArray & |
q_in, |
|
|
KDL::Frame & |
p_out, |
|
|
int |
segmentNr = -1 |
|
) |
| |
|
override |
- Parameters
-
q_in | Input joint coordinates. |
p_out | Reference to output cartesian pose. |
segmentNr | Desired segment frame (unsupported). |
- Returns
- Return code, < 0 if something went wrong.
◆ JntToCart() [2/2]
int ChainFkSolverPos_ST::JntToCart |
( |
const KDL::JntArray & |
q_in, |
|
|
std::vector< KDL::Frame > & |
p_out, |
|
|
int |
segmentNr = -1 |
|
) |
| |
|
override |
- Parameters
-
q_in | Input joint coordinates. |
p_out | Reference to a vector of output cartesian poses for all segments. |
segmentNr | Last selected segment frame. |
- Returns
- Return code, < 0 if something went wrong.
- Warning
- Unsupported, will return E_OPERATION_NOT_SUPPORTED.
◆ strError()
const char * ChainFkSolverPos_ST::strError |
( |
const int |
error | ) |
const |
|
override |
- Parameters
-
- Returns
- If
error
is known then a description of error
, otherwise "UNKNOWN ERROR".
◆ updateInternalDataStructures()
void ChainFkSolverPos_ST::updateInternalDataStructures |
( |
| ) |
|
|
override |
Update the internal data structures. This is required if the number of segments or number of joints of a chain has changed. This provides a single point of contact for solver memory allocations.
The documentation for this class was generated from the following files: