#include <chainiksolver_pos_nr_jl_mimic.hpp>
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_NR_JL_Mimic (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6, bool position_ik=false) | |
bool | setMimicJoints (const std::vector< kdl_kinematics_plugin::JointMimic > &mimic_joints) |
~ChainIkSolverPos_NR_JL_Mimic () | |
Private Member Functions | |
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 |
ChainIkSolverVel & | iksolver |
unsigned int | maxiter |
std::vector < kdl_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 |
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations to calculate the position transformation from Cartesian to joint space of a general KDL::Chain. Takes joint limits into account.
Definition at line 47 of file chainiksolver_pos_nr_jl_mimic.hpp.
KDL::ChainIkSolverPos_NR_JL_Mimic::ChainIkSolverPos_NR_JL_Mimic | ( | const Chain & | chain, |
const JntArray & | q_min, | ||
const JntArray & | q_max, | ||
ChainFkSolverPos & | fksolver, | ||
ChainIkSolverVel & | 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 Newton-Raphson iterations, default: 100 |
eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
Definition at line 34 of file chainiksolver_pos_nr_jl_mimic.cpp.
Definition at line 159 of file chainiksolver_pos_nr_jl_mimic.cpp.
int KDL::ChainIkSolverPos_NR_JL_Mimic::CartToJnt | ( | const JntArray & | q_init, |
const Frame & | p_in, | ||
JntArray & | q_out | ||
) | [virtual] |
Implements KDL::ChainIkSolverPos.
Definition at line 86 of file chainiksolver_pos_nr_jl_mimic.cpp.
int KDL::ChainIkSolverPos_NR_JL_Mimic::CartToJntAdvanced | ( | const JntArray & | q_init, |
const Frame & | p_in, | ||
JntArray & | q_out, | ||
bool | lock_redundant_joints | ||
) | [virtual] |
Definition at line 91 of file chainiksolver_pos_nr_jl_mimic.cpp.
void KDL::ChainIkSolverPos_NR_JL_Mimic::qMimicToq | ( | const JntArray & | q, |
JntArray & | q_result | ||
) | [private] |
Definition at line 75 of file chainiksolver_pos_nr_jl_mimic.cpp.
void KDL::ChainIkSolverPos_NR_JL_Mimic::qToqMimic | ( | const JntArray & | q, |
JntArray & | q_result | ||
) | [private] |
Definition at line 67 of file chainiksolver_pos_nr_jl_mimic.cpp.
bool KDL::ChainIkSolverPos_NR_JL_Mimic::setMimicJoints | ( | const std::vector< kdl_kinematics_plugin::JointMimic > & | mimic_joints | ) |
Definition at line 41 of file chainiksolver_pos_nr_jl_mimic.cpp.
const Chain KDL::ChainIkSolverPos_NR_JL_Mimic::chain [private] |
Definition at line 78 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::delta_q [private] |
Definition at line 86 of file chainiksolver_pos_nr_jl_mimic.hpp.
Definition at line 88 of file chainiksolver_pos_nr_jl_mimic.hpp.
double KDL::ChainIkSolverPos_NR_JL_Mimic::eps [private] |
Definition at line 90 of file chainiksolver_pos_nr_jl_mimic.hpp.
Frame KDL::ChainIkSolverPos_NR_JL_Mimic::f [private] |
Definition at line 87 of file chainiksolver_pos_nr_jl_mimic.hpp.
Definition at line 84 of file chainiksolver_pos_nr_jl_mimic.hpp.
Definition at line 85 of file chainiksolver_pos_nr_jl_mimic.hpp.
unsigned int KDL::ChainIkSolverPos_NR_JL_Mimic::maxiter [private] |
Definition at line 89 of file chainiksolver_pos_nr_jl_mimic.hpp.
std::vector<kdl_kinematics_plugin::JointMimic> KDL::ChainIkSolverPos_NR_JL_Mimic::mimic_joints [private] |
Definition at line 91 of file chainiksolver_pos_nr_jl_mimic.hpp.
bool KDL::ChainIkSolverPos_NR_JL_Mimic::position_ik [private] |
Definition at line 94 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::q_max [private] |
Definition at line 81 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::q_max_mimic [private] |
Definition at line 82 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::q_min [private] |
Definition at line 79 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::q_min_mimic [private] |
Definition at line 80 of file chainiksolver_pos_nr_jl_mimic.hpp.
JntArray KDL::ChainIkSolverPos_NR_JL_Mimic::q_temp [private] |
Definition at line 83 of file chainiksolver_pos_nr_jl_mimic.hpp.