IK solver using Screw Theory.
More...
#include <ChainIkSolverPos_ST.hpp>
Implementation of an inverse position kinematics algorithm. This is a thin wrapper around ScrewTheoryIkProblem. Non-exhaustive tests on TEO's (UC3M) right arm kinematic chain reveal that this is 5-10 faster than a numeric Newton-Raphson solver as provided by KDL (e.g. KDL::ChainIkSolverPos_NR_JL).
◆ CartToJnt()
int ChainIkSolverPos_ST::CartToJnt |
( |
const KDL::JntArray & |
q_init, |
|
|
const KDL::Frame & |
p_in, |
|
|
KDL::JntArray & |
q_out |
|
) |
| |
|
override |
- Parameters
-
q_init | Initial guess of the joint coordinates (unused). |
p_in | Input cartesian coordinates. |
q_out | Output joint coordinates. |
- Returns
- Return code, E_SOLUTION_NOT_FOUND if there is no solution or E_NOT_REACHABLE if at least one of them is out of reach.
◆ create()
- Parameters
-
chain | Input kinematic chain. |
configFactory | Instance of an abstract factory class that instantiates a ConfigurationSelector. |
- Returns
- Solver instance or null if no solution was found.
◆ strError()
const char * ChainIkSolverPos_ST::strError |
( |
const int |
error | ) |
const |
|
override |
- Parameters
-
- Returns
- If
error
is known then a description of error
, otherwise "UNKNOWN ERROR".
◆ updateInternalDataStructures()
void ChainIkSolverPos_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: