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;
94 const Eigen::Matrix<double,6,1>& _L,
97 double _eps_joints=1E-15
109 double _eps_joints=1E-15
212 Eigen::Matrix<ScalarType,6,1>
L;
230 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:209
Eigen::JacobiSVD< MatrixXq > svd
Definition: chainiksolverpos_lma.hpp:230
KDL::Frame T_base_head
for internal use only.
Definition: chainiksolverpos_lma.hpp:199
double lastRotDiff
contains the last value for the (unweighted) rotational difference after an execution of CartToJnt...
Definition: chainiksolverpos_lma.hpp:174
std::vector< KDL::Frame > T_base_jointtip
Definition: chainiksolverpos_lma.hpp:218
This class encapsulates a serial kinematic interconnection structure.
Definition: chain.hpp:35
double eps_joints
Definition: chainiksolverpos_lma.hpp:211
bool display_information
display information on each iteration step to the console.
Definition: chainiksolverpos_lma.hpp:204
void compute_jacobian(const VectorXq &q)
for internal use only.
Definition: chainiksolverpos_lma.cpp:131
MatrixXq A
Definition: chainiksolverpos_lma.hpp:227
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:150
VectorXq lastSV
contains the last values for the singular values of the weighted Jacobian after an execution of CartT...
Definition: chainiksolverpos_lma.hpp:179
double eps
Definition: chainiksolverpos_lma.hpp:210
const KDL::Chain & chain
Definition: chainiksolverpos_lma.hpp:213
VectorXq q_new
Definition: chainiksolverpos_lma.hpp:232
MatrixXq jac
for internal use only.
Definition: chainiksolverpos_lma.hpp:186
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:159
Eigen::Matrix< ScalarType, 6, 1 > L
Definition: chainiksolverpos_lma.hpp:212
double lastDifference
contains the last value for after an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:164
VectorXq grad
for internal use only.
Definition: chainiksolverpos_lma.hpp:193
void compute_fwdpos(const VectorXq &q)
for internal use only.
Definition: chainiksolverpos_lma.cpp:114
double lastTransDiff
contains the last value for the (unweighted) translational difference after an execution of CartToJnt...
Definition: chainiksolverpos_lma.hpp:169
Eigen::LDLT< MatrixXq > ldlt
Definition: chainiksolverpos_lma.hpp:229
VectorXq tmp
Definition: chainiksolverpos_lma.hpp:228
VectorXq q
Definition: chainiksolverpos_lma.hpp:226
std::vector< KDL::Frame > T_base_jointroot
Definition: chainiksolverpos_lma.hpp:217
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:570
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:160
VectorXq diffq
Definition: chainiksolverpos_lma.hpp:231
Eigen::Matrix< ScalarType, Eigen::Dynamic, Eigen::Dynamic > MatrixXq
Definition: chainiksolverpos_lma.hpp:68
virtual ~ChainIkSolverPos_LMA()
destructor.
Definition: chainiksolverpos_lma.cpp:112
VectorXq original_Aii
Definition: chainiksolverpos_lma.hpp:233
Eigen::Matrix< ScalarType, Eigen::Dynamic, 1 > VectorXq
Definition: chainiksolverpos_lma.hpp:69
double ScalarType
Definition: chainiksolverpos_lma.hpp:67