Public Member Functions | Private Member Functions | Private Attributes
KDL::ChainIkSolverPos_NR_JL_Mimic Class Reference

#include <chainiksolver_pos_nr_jl_mimic.hpp>

Inheritance diagram for KDL::ChainIkSolverPos_NR_JL_Mimic:
Inheritance graph
[legend]

List of all members.

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
ChainFkSolverPosfksolver
ChainIkSolverVeliksolver
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

Detailed Description

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 46 of file chainiksolver_pos_nr_jl_mimic.hpp.


Constructor & Destructor Documentation

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.

Parameters:
chainthe chain to calculate the inverse position for
q_maxthe maximum joint positions
q_minthe minimum joint positions
fksolvera forward position kinematics solver
iksolveran inverse velocity kinematics solver
maxiterthe maximum Newton-Raphson iterations, default: 100
epsthe precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp)
Returns:

Definition at line 33 of file chainiksolver_pos_nr_jl_mimic.cpp.

Definition at line 194 of file chainiksolver_pos_nr_jl_mimic.cpp.


Member Function Documentation

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 110 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 115 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 99 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 91 of file chainiksolver_pos_nr_jl_mimic.cpp.

Definition at line 63 of file chainiksolver_pos_nr_jl_mimic.cpp.


Member Data Documentation

Definition at line 79 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 87 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 89 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 91 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 88 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 85 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 86 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 90 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 92 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 96 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 82 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 83 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 80 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 81 of file chainiksolver_pos_nr_jl_mimic.hpp.

Definition at line 84 of file chainiksolver_pos_nr_jl_mimic.hpp.


The documentation for this class was generated from the following files:


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Wed Jun 19 2019 19:24:24