Public Member Functions | Private Member Functions | Private Attributes | List of all members
KDL::ChainIkSolverPos_LMA_JL_Mimic Class Reference

#include <chainiksolver_pos_lma_jl_mimic.h>

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

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
 
ChainFkSolverPosfksolver
 
ChainIkSolverPos_LMAiksolver
 
unsigned int maxiter
 
std::vector< lma_kinematics_plugin::JointMimicmimic_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
 

Detailed Description

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.

Constructor & Destructor Documentation

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.

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 Levenberg-Marquardt iterations, default: 100
epsthe precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp)
Returns

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.

Member Function Documentation

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.

Member Data Documentation

const Chain KDL::ChainIkSolverPos_LMA_JL_Mimic::chain
private

Definition at line 88 of file chainiksolver_pos_lma_jl_mimic.h.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::delta_q
private

Definition at line 96 of file chainiksolver_pos_lma_jl_mimic.h.

Twist KDL::ChainIkSolverPos_LMA_JL_Mimic::delta_twist
private

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.

ChainFkSolverPos& KDL::ChainIkSolverPos_LMA_JL_Mimic::fksolver
private

Definition at line 94 of file chainiksolver_pos_lma_jl_mimic.h.

ChainIkSolverPos_LMA& KDL::ChainIkSolverPos_LMA_JL_Mimic::iksolver
private

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.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::q_max
private

Definition at line 91 of file chainiksolver_pos_lma_jl_mimic.h.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::q_max_mimic
private

Definition at line 92 of file chainiksolver_pos_lma_jl_mimic.h.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::q_min
private

Definition at line 89 of file chainiksolver_pos_lma_jl_mimic.h.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::q_min_mimic
private

Definition at line 90 of file chainiksolver_pos_lma_jl_mimic.h.

JntArray KDL::ChainIkSolverPos_LMA_JL_Mimic::q_temp
private

Definition at line 93 of file chainiksolver_pos_lma_jl_mimic.h.


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


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Wed Jul 10 2019 04:03:42