Public Member Functions | Public Attributes | Static Public Attributes | Private Types | Private Attributes
KDL::ChainIkSolverPos_LMA Class Reference

Solver for the inverse position kinematics that uses Levenberg-Marquardt. More...

#include <chainiksolverpos_lma.hpp>

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

List of all members.

Public Member Functions

virtual int CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &T_base_goal, KDL::JntArray &q_out)
 computes the inverse position kinematics.
 ChainIkSolverPos_LMA (const KDL::Chain &_chain, const Eigen::Matrix< double, 6, 1 > &_L, double _eps=1E-5, int _maxiter=500, double _eps_joints=1E-15)
 constructs an ChainIkSolverPos_LMA solver.
 ChainIkSolverPos_LMA (const KDL::Chain &_chain, double _eps=1E-5, int _maxiter=500, double _eps_joints=1E-15)
 identical the full constructor for ChainIkSolverPos_LMA, but provides for a default weight matrix.
void compute_fwdpos (const VectorXq &q)
 for internal use only.
void compute_jacobian (const VectorXq &q)
 for internal use only. Only exposed for test and diagnostic purposes. compute_fwdpos(q) should always have been called before.
void display_jac (const KDL::JntArray &jval)
 for internal use only. Only exposed for test and diagnostic purposes.
virtual const char * strError (const int error) const
void updateInternalDataStructures ()
virtual ~ChainIkSolverPos_LMA ()
 destructor.

Public Attributes

bool display_information
 display information on each iteration step to the console.
VectorXq grad
 for internal use only.
MatrixXq jac
 for internal use only.
double lastDifference
 contains the last value for $ E $ after an execution of CartToJnt.
int lastNrOfIter
 contains the last number of iterations for an execution of CartToJnt.
double lastRotDiff
 contains the last value for the (unweighted) rotational difference after an execution of CartToJnt.
VectorXq lastSV
 contains the last values for the singular values of the weighted Jacobian after an execution of CartToJnt.
double lastTransDiff
 contains the last value for the (unweighted) translational difference after an execution of CartToJnt.
KDL::Frame T_base_head
 for internal use only.

Static Public Attributes

static const int E_GRADIENT_JOINTS_TOO_SMALL = -100
static const int E_INCREMENT_JOINTS_TOO_SMALL = -101

Private Types

typedef Eigen::Matrix
< ScalarType, Eigen::Dynamic,
Eigen::Dynamic > 
MatrixXq
typedef double ScalarType
typedef Eigen::Matrix
< ScalarType, Eigen::Dynamic, 1 > 
VectorXq

Private Attributes

MatrixXq A
const KDL::Chainchain
VectorXq diffq
double eps
double eps_joints
Eigen::Matrix< ScalarType, 6, 1 > L
Eigen::LDLT< MatrixXqldlt
unsigned int maxiter
unsigned int nj
unsigned int ns
VectorXq original_Aii
VectorXq q
VectorXq q_new
Eigen::JacobiSVD< MatrixXqsvd
std::vector< KDL::FrameT_base_jointroot
std::vector< KDL::FrameT_base_jointtip
VectorXq tmp

Detailed Description

Solver for the inverse position kinematics that uses Levenberg-Marquardt.

The robustness and speed of this solver is improved in several ways:

De general principles behind the optimisation is inspired on: Jorge Nocedal, Stephen J. Wright, Numerical Optimization,Springer-Verlag New York, 1999.

Definition at line 64 of file chainiksolverpos_lma.hpp.


Member Typedef Documentation

typedef Eigen::Matrix<ScalarType,Eigen::Dynamic,Eigen::Dynamic> KDL::ChainIkSolverPos_LMA::MatrixXq [private]

Definition at line 68 of file chainiksolverpos_lma.hpp.

typedef double KDL::ChainIkSolverPos_LMA::ScalarType [private]

Definition at line 67 of file chainiksolverpos_lma.hpp.

typedef Eigen::Matrix<ScalarType,Eigen::Dynamic,1> KDL::ChainIkSolverPos_LMA::VectorXq [private]

Definition at line 69 of file chainiksolverpos_lma.hpp.


Constructor & Destructor Documentation

KDL::ChainIkSolverPos_LMA::ChainIkSolverPos_LMA ( const KDL::Chain _chain,
const Eigen::Matrix< double, 6, 1 > &  _L,
double  _eps = 1E-5,
int  _maxiter = 500,
double  _eps_joints = 1E-15 
)

constructs an ChainIkSolverPos_LMA solver.

The default parameters are chosen to be applicable to industrial-size robots (e.g. 0.5 to 3 meters range in task space), with an accuracy that is more then sufficient for typical industrial applications.

Weights are applied in task space, i.e. the kinematic solver minimizes: $ E = \Delta \mathbf{x}^T \mathbf{L} \mathbf{L}^T \Delta \mathbf{x} $, with $\mathbf{L}$ a diagonal matrix.

Parameters:
_chainspecifies the kinematic chain.
_Lspecifies the "square root" of the weight (diagonal) matrix in task space. This diagonal matrix is specified as a vector.
_epsspecifies the desired accuracy in task space; after weighing with the weight matrix, it is applied on $E$.
_maxiterspecifies the maximum number of iterations.
_eps_jointsspecifies that the algorithm has to stop when the computed joint angle increments are smaller then _eps_joints. This is to avoid unnecessary computations up to _maxiter when the joint angle increments are so small that they effectively (in floating point) do not change the joint angles any more. The default is a few digits above numerical accuracy.

Definition at line 50 of file chainiksolverpos_lma.cpp.

KDL::ChainIkSolverPos_LMA::ChainIkSolverPos_LMA ( const KDL::Chain _chain,
double  _eps = 1E-5,
int  _maxiter = 500,
double  _eps_joints = 1E-15 
)

identical the full constructor for ChainIkSolverPos_LMA, but provides for a default weight matrix.

$\mathbf{L} = \mathrm{diag}\left( \begin{bmatrix} 1 & 1 & 1 & 0.01 & 0.01 & 0.01 \end{bmatrix} \right) $.

Definition at line 84 of file chainiksolverpos_lma.cpp.

destructor.

Definition at line 139 of file chainiksolverpos_lma.cpp.


Member Function Documentation

int KDL::ChainIkSolverPos_LMA::CartToJnt ( const KDL::JntArray q_init,
const KDL::Frame T_base_goal,
KDL::JntArray q_out 
) [virtual]

computes the inverse position kinematics.

Parameters:
q_initinitial joint position.
T_base_goalgoal position expressed with respect to the robot base.
q_outjoint position that achieves the specified goal position (if successful).
Returns:
E_NOERROR if successful, E_GRADIENT_JOINTS_TOO_SMALL the gradient of $ E $ towards the joints is to small, E_INCREMENT_JOINTS_TOO_SMALL if joint position increments are to small, E_MAX_ITER_EXCEEDED if number of iterations is exceeded.

Implements KDL::ChainIkSolverPos.

Definition at line 187 of file chainiksolverpos_lma.cpp.

for internal use only.

Only exposed for test and diagnostic purposes.

Definition at line 141 of file chainiksolverpos_lma.cpp.

for internal use only. Only exposed for test and diagnostic purposes. compute_fwdpos(q) should always have been called before.

Definition at line 158 of file chainiksolverpos_lma.cpp.

for internal use only. Only exposed for test and diagnostic purposes.

Definition at line 177 of file chainiksolverpos_lma.cpp.

const char * KDL::ChainIkSolverPos_LMA::strError ( const int  error) const [virtual]

Return a description of the latest error

Returns:
if error is known then a description of error, otherwise "UNKNOWN ERROR"

Reimplemented from KDL::SolverI.

Definition at line 317 of file chainiksolverpos_lma.cpp.

Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::ChainIkSolverPos.

Definition at line 122 of file chainiksolverpos_lma.cpp.


Member Data Documentation

Definition at line 236 of file chainiksolverpos_lma.hpp.

Definition at line 160 of file chainiksolverpos_lma.hpp.

Definition at line 240 of file chainiksolverpos_lma.hpp.

display information on each iteration step to the console.

Definition at line 215 of file chainiksolverpos_lma.hpp.

Definition at line 72 of file chainiksolverpos_lma.hpp.

Definition at line 73 of file chainiksolverpos_lma.hpp.

Definition at line 219 of file chainiksolverpos_lma.hpp.

Definition at line 220 of file chainiksolverpos_lma.hpp.

for internal use only.

contains the gradient of the error criterion after an execution of CartToJnt.

Definition at line 204 of file chainiksolverpos_lma.hpp.

for internal use only.

contains the last value for the Jacobian after an execution of compute_jacobian.

Definition at line 197 of file chainiksolverpos_lma.hpp.

Eigen::Matrix<ScalarType,6,1> KDL::ChainIkSolverPos_LMA::L [private]

Definition at line 221 of file chainiksolverpos_lma.hpp.

contains the last value for $ E $ after an execution of CartToJnt.

Definition at line 175 of file chainiksolverpos_lma.hpp.

contains the last number of iterations for an execution of CartToJnt.

Definition at line 170 of file chainiksolverpos_lma.hpp.

contains the last value for the (unweighted) rotational difference after an execution of CartToJnt.

Definition at line 185 of file chainiksolverpos_lma.hpp.

contains the last values for the singular values of the weighted Jacobian after an execution of CartToJnt.

Definition at line 190 of file chainiksolverpos_lma.hpp.

contains the last value for the (unweighted) translational difference after an execution of CartToJnt.

Definition at line 180 of file chainiksolverpos_lma.hpp.

Eigen::LDLT<MatrixXq> KDL::ChainIkSolverPos_LMA::ldlt [private]

Definition at line 238 of file chainiksolverpos_lma.hpp.

unsigned int KDL::ChainIkSolverPos_LMA::maxiter [private]

Definition at line 218 of file chainiksolverpos_lma.hpp.

unsigned int KDL::ChainIkSolverPos_LMA::nj [private]

Definition at line 161 of file chainiksolverpos_lma.hpp.

unsigned int KDL::ChainIkSolverPos_LMA::ns [private]

Definition at line 162 of file chainiksolverpos_lma.hpp.

Definition at line 242 of file chainiksolverpos_lma.hpp.

Definition at line 235 of file chainiksolverpos_lma.hpp.

Definition at line 241 of file chainiksolverpos_lma.hpp.

Eigen::JacobiSVD<MatrixXq> KDL::ChainIkSolverPos_LMA::svd [private]

Definition at line 239 of file chainiksolverpos_lma.hpp.

for internal use only.

contains the last value for the position of the tip of the robot (head) with respect to the base, after an execution of compute_jacobian.

Definition at line 210 of file chainiksolverpos_lma.hpp.

Definition at line 226 of file chainiksolverpos_lma.hpp.

Definition at line 227 of file chainiksolverpos_lma.hpp.

Definition at line 237 of file chainiksolverpos_lma.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Jun 14 2019 19:33:23