#include <chainiksolver_pos_lma_jl_mimic.h>
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.
Definition at line 166 of file chainiksolver_pos_lma_jl_mimic.cpp.
int KDL::ChainIkSolverPos_LMA_JL_Mimic::CartToJnt | ( | const JntArray & | q_init, |
const Frame & | p_in, | ||
JntArray & | q_out | ||
) | [virtual] |
Implements KDL::ChainIkSolverPos.
Definition at line 119 of file chainiksolver_pos_lma_jl_mimic.cpp.
int KDL::ChainIkSolverPos_LMA_JL_Mimic::CartToJntAdvanced | ( | const JntArray & | q_init, |
const Frame & | p_in, | ||
JntArray & | q_out, | ||
bool | lock_redundant_joints | ||
) | [virtual] |
Definition at line 154 of file chainiksolver_pos_lma_jl_mimic.cpp.
void KDL::ChainIkSolverPos_LMA_JL_Mimic::harmonize | ( | JntArray & | q_out | ) | [private] |
Definition at line 124 of file chainiksolver_pos_lma_jl_mimic.cpp.
bool KDL::ChainIkSolverPos_LMA_JL_Mimic::obeysLimits | ( | const KDL::JntArray & | q_out | ) | [private] |
Definition at line 137 of file chainiksolver_pos_lma_jl_mimic.cpp.
void KDL::ChainIkSolverPos_LMA_JL_Mimic::qMimicToq | ( | const JntArray & | q, |
JntArray & | q_result | ||
) | [private] |
Definition at line 108 of file chainiksolver_pos_lma_jl_mimic.cpp.
void KDL::ChainIkSolverPos_LMA_JL_Mimic::qToqMimic | ( | const JntArray & | q, |
JntArray & | q_result | ||
) | [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.
const Chain KDL::ChainIkSolverPos_LMA_JL_Mimic::chain [private] |
Definition at line 88 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 96 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 98 of file chainiksolver_pos_lma_jl_mimic.h.
double KDL::ChainIkSolverPos_LMA_JL_Mimic::eps [private] |
Definition at line 100 of file chainiksolver_pos_lma_jl_mimic.h.
Frame KDL::ChainIkSolverPos_LMA_JL_Mimic::f [private] |
Definition at line 97 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 94 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 95 of file chainiksolver_pos_lma_jl_mimic.h.
unsigned int KDL::ChainIkSolverPos_LMA_JL_Mimic::maxiter [private] |
Definition at line 99 of file chainiksolver_pos_lma_jl_mimic.h.
std::vector<lma_kinematics_plugin::JointMimic> KDL::ChainIkSolverPos_LMA_JL_Mimic::mimic_joints [private] |
Definition at line 101 of file chainiksolver_pos_lma_jl_mimic.h.
bool KDL::ChainIkSolverPos_LMA_JL_Mimic::position_ik [private] |
Definition at line 107 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 91 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 92 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 89 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 90 of file chainiksolver_pos_lma_jl_mimic.h.
Definition at line 93 of file chainiksolver_pos_lma_jl_mimic.h.