#include <chainiksolver_pos_lma_jl_mimic.h>

Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out) |
| virtual int | CartToJntAdvanced (const JntArray &q_init, const Frame &p_in, JntArray &q_out, bool lock_redundant_joints) |
| ChainIkSolverPos_LMA_JL_Mimic (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverPos_LMA &iksolver, unsigned int maxiter=100, double eps=1e-6, bool position_ik=false) | |
| bool | setMimicJoints (const std::vector< lma_kinematics_plugin::JointMimic > &mimic_joints) |
| ~ChainIkSolverPos_LMA_JL_Mimic () | |
Public Member Functions inherited from KDL::ChainIkSolverPos | |
| virtual void | updateInternalDataStructures ()=0 |
| virtual | ~ChainIkSolverPos () |
Public Member Functions inherited from KDL::SolverI | |
| virtual int | getError () const |
| SolverI () | |
| virtual const char * | strError (const int error) const |
| virtual | ~SolverI () |
Private Member Functions | |
| void | harmonize (JntArray &q_out) |
| bool | obeysLimits (const KDL::JntArray &q_out) |
| void | qMimicToq (const JntArray &q, JntArray &q_result) |
| void | qToqMimic (const JntArray &q, JntArray &q_result) |
Private Attributes | |
| const Chain | chain |
| JntArray | delta_q |
| Twist | delta_twist |
| double | eps |
| Frame | f |
| ChainFkSolverPos & | fksolver |
| ChainIkSolverPos_LMA & | iksolver |
| unsigned int | maxiter |
| std::vector< lma_kinematics_plugin::JointMimic > | mimic_joints |
| bool | position_ik |
| JntArray | q_max |
| JntArray | q_max_mimic |
| JntArray | q_min |
| JntArray | q_min_mimic |
| JntArray | q_temp |
Additional Inherited Members | |
Public Attributes inherited from KDL::SolverI | |
| E_DEGRADED | |
| E_MAX_ITERATIONS_EXCEEDED | |
| E_NO_CONVERGE | |
| E_NOERROR | |
| E_NOT_IMPLEMENTED | |
| E_NOT_UP_TO_DATE | |
| E_OUT_OF_RANGE | |
| E_SIZE_MISMATCH | |
| E_SVD_FAILED | |
| E_UNDEFINED | |
Protected Attributes inherited from KDL::SolverI | |
| int | error |
Implementation of a general inverse position kinematics algorithm based on Levenberg-Marquardt method to calculate the position transformation from Cartesian to joint space of a general KDL::Chain. Takes joint limits into account.
Definition at line 55 of file chainiksolver_pos_lma_jl_mimic.h.
| KDL::ChainIkSolverPos_LMA_JL_Mimic::ChainIkSolverPos_LMA_JL_Mimic | ( | const Chain & | chain, |
| const JntArray & | q_min, | ||
| const JntArray & | q_max, | ||
| ChainFkSolverPos & | fksolver, | ||
| ChainIkSolverPos_LMA & | iksolver, | ||
| unsigned int | maxiter = 100, |
||
| double | eps = 1e-6, |
||
| bool | position_ik = false |
||
| ) |
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
| chain | the chain to calculate the inverse position for |
| q_max | the maximum joint positions |
| q_min | the minimum joint positions |
| fksolver | a forward position kinematics solver |
| iksolver | an inverse velocity kinematics solver |
| maxiter | the maximum Levenberg-Marquardt iterations, default: 100 |
| eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
Definition at line 42 of file chainiksolver_pos_lma_jl_mimic.cpp.
| KDL::ChainIkSolverPos_LMA_JL_Mimic::~ChainIkSolverPos_LMA_JL_Mimic | ( | ) |
Definition at line 166 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
virtual |
Implements KDL::ChainIkSolverPos.
Definition at line 119 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
virtual |
Definition at line 154 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
private |
Definition at line 124 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
private |
Definition at line 137 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
private |
Definition at line 108 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
private |
Definition at line 100 of file chainiksolver_pos_lma_jl_mimic.cpp.
| bool KDL::ChainIkSolverPos_LMA_JL_Mimic::setMimicJoints | ( | const std::vector< lma_kinematics_plugin::JointMimic > & | mimic_joints | ) |
Definition at line 72 of file chainiksolver_pos_lma_jl_mimic.cpp.
|
private |
Definition at line 88 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 96 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 98 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 100 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 97 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 94 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 95 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 99 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 101 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 107 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 91 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 92 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 89 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 90 of file chainiksolver_pos_lma_jl_mimic.h.
|
private |
Definition at line 93 of file chainiksolver_pos_lma_jl_mimic.h.