57 #include <boost/timer.hpp> 68 int num_of_trials = 1000000;
69 int total_number_of_iter = 0;
71 int nrofresult_ok = 0;
72 int nrofresult_minus1=0;
73 int nrofresult_minus2=0;
74 int nrofresult_minus3=0;
75 int min_num_of_iter = 10000000;
76 int max_num_of_iter = 0;
77 double min_diff = 1E10;
79 double min_trans_diff = 1E10;
80 double max_trans_diff = 0;
81 double min_rot_diff = 1E10;
82 double max_rot_diff = 0;
83 Eigen::Matrix<double,6,1> L;
85 L(3)=0.01;L(4)=0.01;L(5)=0.01;
91 for (
int trial=0;trial<num_of_trials;++trial) {
94 q_init.
data.setRandom();
96 Frame pos_goal,pos_reached;
101 retval = solver.
CartToJnt(q_init,pos_goal,q_sol);
117 cout <<
"-------------- failed ----------------------------" << endl;
118 cout <<
"pos " << pos_goal << endl;
119 cout <<
"reached pos " << solver.
T_base_head << endl;
121 cout <<
"gradient " << solver.
grad.transpose() << endl;
122 cout <<
"q " << q.
data.transpose()/M_PI*180.0 << endl;
123 cout <<
"q_sol " << q_sol.
data.transpose()/M_PI*180.0 << endl;
124 cout <<
"q_init " << q_init.
data.transpose()/M_PI*180.0 << endl;
125 cout <<
"return value " << retval << endl;
128 cout <<
"jacobian of goal values ";
130 std::cout <<
"jacobian of solved values ";
149 cout <<
"------------------ statistics ------------------------------"<<endl;
150 cout <<
"#times successful " << nrofresult_ok << endl;
151 cout <<
"#times -1 result " << nrofresult_minus1 << endl;
152 cout <<
"#times -2 result " << nrofresult_minus2 << endl;
153 cout <<
"#times -3 result " << nrofresult_minus3 << endl;
154 cout <<
"average number of iter " << (double)total_number_of_iter/(
double)num_of_trials << endl;
155 cout <<
"min. nr of iter " << min_num_of_iter << endl;
156 cout <<
"max. nr of iter " << max_num_of_iter << endl;
157 cout <<
"min. difference after solving " << min_diff << endl;
158 cout <<
"max. difference after solving " << max_diff << endl;
159 cout <<
"min. trans. difference after solving " << min_trans_diff << endl;
160 cout <<
"max. trans. difference after solving " << max_trans_diff << endl;
161 cout <<
"min. rot. difference after solving " << min_rot_diff << endl;
162 cout <<
"max. rot. difference after solving " << max_rot_diff << endl;
163 double el = timer.elapsed();
164 cout <<
"elapsed time " << el << endl;
165 cout <<
"estimate of average time per invposkin (ms)" << el/num_of_trials*1000 << endl;
166 cout <<
"estimate of longest time per invposkin (ms) " << el/total_number_of_iter*max_num_of_iter *1000 << endl;
167 cout <<
"estimate of shortest time per invposkin (ms) " << el/total_number_of_iter*min_num_of_iter *1000 << endl;
170 int main(
int argc,
char* argv[]) {
172 " This example generates random joint positions, applies a forward kinematic transformation,\n" 173 <<
" and calls ChainIkSolverPos_LMA on the resulting pose. In this way we are sure that\n" 174 <<
" the resulting pose is reachable. However, some percentage of the trials will be at\n" 175 <<
" near singular position, where it is more difficult to achieve convergence and accuracy\n" 176 <<
" The initial position given to the algorithm is also a random joint position\n" 177 <<
" This routine asks for an accuracy of 10 micrometer, one order of magnitude better than a\n" 178 <<
" a typical industrial robot.\n" 179 <<
" This routine can take more then 6 minutes to execute. It then gives statistics on execution times\n" 180 <<
" and failures.\n" 181 <<
" Typically when executed 1 000 000 times, you will still see some small amount of failures\n" 182 <<
" Typically these failures are in the neighbourhoud of singularities. Most failures of type -2 still\n" 183 <<
" reach an accuracy better than 1E-4.\n" 184 <<
" This is much better than ChainIkSolverPos_NR, which fails a few times per 100 trials.\n";
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
KDL::Frame T_base_head
for internal use only.
double lastRotDiff
contains the last value for the (unweighted) rotational difference after an execution of CartToJnt...
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
This class represents an fixed size array containing joint values of a KDL::Chain.
void display_jac(const KDL::JntArray &jval)
for internal use only. Only exposed for test and diagnostic purposes.
computing inverse position kinematics using Levenberg-Marquardt.
Solver for the inverse position kinematics that uses Levenberg-Marquardt.
int lastNrOfIter
contains the last number of iterations for an execution of CartToJnt.
int main(int argc, char *argv[])
unsigned int getNrOfJoints() const
Frame Inverse() const
Gives back inverse transformation of a Frame.
double lastDifference
contains the last value for after an execution of CartToJnt.
VectorXq grad
for internal use only.
double lastTransDiff
contains the last value for the (unweighted) translational difference after an execution of CartToJnt...
represents a frame transformation in 3D space (rotation + translation)
void test_inverseposkin(KDL::Chain &chain)
virtual int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &T_base_goal, KDL::JntArray &q_out)
computes the inverse position kinematics.