IK solver using infinitesimal displacement twists.
More...
#include <ChainIkSolverPos_ID.hpp>
|
| ChainIkSolverPos_ID (const KDL::Chain &chain, const KDL::JntArray &q_min, const KDL::JntArray &q_max, KDL::ChainFkSolverPos &fksolver) |
| Constructor. More...
|
|
int | CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override |
| Calculate inverse position kinematics. 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...
|
|
|
KDL::JntArray | computeDiffInvKin (const KDL::Twist &delta_twist) |
|
|
const KDL::Chain & | chain |
|
unsigned int | nj |
|
KDL::JntArray | qMin |
|
KDL::JntArray | qMax |
|
KDL::ChainFkSolverPos & | fkSolverPos |
|
KDL::ChainJntToJacSolver | jacSolver |
|
KDL::Jacobian | jacobian |
|
Re-implementation of KDL::ChainIkSolverPos_NR_JL in which only one iteration step is performed. Aimed to provide a quick means of obtaining IK whenever the displacements are small enough.
◆ ChainIkSolverPos_ID()
ChainIkSolverPos_ID::ChainIkSolverPos_ID |
( |
const KDL::Chain & |
chain, |
|
|
const KDL::JntArray & |
q_min, |
|
|
const KDL::JntArray & |
q_max, |
|
|
KDL::ChainFkSolverPos & |
fksolver |
|
) |
| |
- Parameters
-
chain | The chain to calculate the inverse position for. |
q_min | The minimum joint positions. |
q_max | The maximum joint positions. |
fksolver | A forward position kinematics solver. |
iksolver | An inverse velocity kinematics solver. |
◆ CartToJnt()
int ChainIkSolverPos_ID::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.
◆ strError()
const char * ChainIkSolverPos_ID::strError |
( |
const int |
error | ) |
const |
|
override |
- Parameters
-
- Returns
- If
error
is known then a description of error
, otherwise "UNKNOWN ERROR".
◆ updateInternalDataStructures()
void ChainIkSolverPos_ID::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: