1 #ifndef KDL_CHAINIKSOLVERPOS_GN_HPP 2 #define KDL_CHAINIKSOLVERPOS_GN_HPP 36 #include <Eigen/Dense> 68 typedef Eigen::Matrix<ScalarType,Eigen::Dynamic,Eigen::Dynamic>
MatrixXq;
69 typedef Eigen::Matrix<ScalarType,Eigen::Dynamic,1>
VectorXq;
97 const Eigen::Matrix<double,6,1>& _L,
100 double _eps_joints=1E-15
112 double _eps_joints=1E-15
221 Eigen::Matrix<ScalarType,6,1>
L;
239 Eigen::JacobiSVD<MatrixXq>
svd;
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.
Definition: chainiksolverpos_lma.cpp:50
This abstract class encapsulates the inverse position solver for a KDL::Chain.
Definition: chainiksolver.hpp:42
unsigned int maxiter
Definition: chainiksolverpos_lma.hpp:218
Eigen::JacobiSVD< MatrixXq > svd
Definition: chainiksolverpos_lma.hpp:239
KDL::Frame T_base_head
for internal use only.
Definition: chainiksolverpos_lma.hpp:210
double lastRotDiff
contains the last value for the (unweighted) rotational difference after an execution of CartToJnt...
Definition: chainiksolverpos_lma.hpp:185
std::vector< KDL::Frame > T_base_jointtip
Definition: chainiksolverpos_lma.hpp:227
This class encapsulates a serial kinematic interconnection structure.
Definition: chain.hpp:35
double eps_joints
Definition: chainiksolverpos_lma.hpp:220
bool display_information
display information on each iteration step to the console.
Definition: chainiksolverpos_lma.hpp:215
void compute_jacobian(const VectorXq &q)
for internal use only.
Definition: chainiksolverpos_lma.cpp:158
MatrixXq A
Definition: chainiksolverpos_lma.hpp:236
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
void display_jac(const KDL::JntArray &jval)
for internal use only.
Definition: chainiksolverpos_lma.cpp:177
VectorXq lastSV
contains the last values for the singular values of the weighted Jacobian after an execution of CartT...
Definition: chainiksolverpos_lma.hpp:190
double eps
Definition: chainiksolverpos_lma.hpp:219
const KDL::Chain & chain
Definition: chainiksolverpos_lma.hpp:160
VectorXq q_new
Definition: chainiksolverpos_lma.hpp:241
static const int E_GRADIENT_JOINTS_TOO_SMALL
Definition: chainiksolverpos_lma.hpp:72
MatrixXq jac
for internal use only.
Definition: chainiksolverpos_lma.hpp:197
Definition: articulatedbodyinertia.cpp:28
Solver for the inverse position kinematics that uses Levenberg-Marquardt.
Definition: chainiksolverpos_lma.hpp:64
int lastNrOfIter
contains the last number of iterations for an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:170
unsigned int ns
Definition: chainiksolverpos_lma.hpp:162
void updateInternalDataStructures()
Update the internal data structures.
Definition: chainiksolverpos_lma.cpp:122
Eigen::Matrix< ScalarType, 6, 1 > L
Definition: chainiksolverpos_lma.hpp:221
double lastDifference
contains the last value for after an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:175
VectorXq grad
for internal use only.
Definition: chainiksolverpos_lma.hpp:204
void compute_fwdpos(const VectorXq &q)
for internal use only.
Definition: chainiksolverpos_lma.cpp:141
double lastTransDiff
contains the last value for the (unweighted) translational difference after an execution of CartToJnt...
Definition: chainiksolverpos_lma.hpp:180
Eigen::LDLT< MatrixXq > ldlt
Definition: chainiksolverpos_lma.hpp:238
VectorXq tmp
Definition: chainiksolverpos_lma.hpp:237
unsigned int nj
Definition: chainiksolverpos_lma.hpp:161
VectorXq q
Definition: chainiksolverpos_lma.hpp:235
std::vector< KDL::Frame > T_base_jointroot
Definition: chainiksolverpos_lma.hpp:226
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
static const int E_INCREMENT_JOINTS_TOO_SMALL
Definition: chainiksolverpos_lma.hpp:73
virtual int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &T_base_goal, KDL::JntArray &q_out)
computes the inverse position kinematics.
Definition: chainiksolverpos_lma.cpp:187
VectorXq diffq
Definition: chainiksolverpos_lma.hpp:240
virtual const char * strError(const int error) const
Return a description of the latest error.
Definition: chainiksolverpos_lma.cpp:317
Eigen::Matrix< ScalarType, Eigen::Dynamic, Eigen::Dynamic > MatrixXq
Definition: chainiksolverpos_lma.hpp:68
virtual ~ChainIkSolverPos_LMA()
destructor.
Definition: chainiksolverpos_lma.cpp:139
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
VectorXq original_Aii
Definition: chainiksolverpos_lma.hpp:242
Eigen::Matrix< ScalarType, Eigen::Dynamic, 1 > VectorXq
Definition: chainiksolverpos_lma.hpp:69
double ScalarType
Definition: chainiksolverpos_lma.hpp:67