orocos_kdl
chainiksolverpos_lma_demo.cpp
Go to the documentation of this file.
1 
27 /**************************************************************************
28  begin : May 2011
29  copyright : (C) 2011 Erwin Aertbelien
30  email : firstname.lastname@mech.kuleuven.ac.be
31 
32  History (only major changes)( AUTHOR-Description ) :
33 
34  ***************************************************************************
35  * This library is free software; you can redistribute it and/or *
36  * modify it under the terms of the GNU Lesser General Public *
37  * License as published by the Free Software Foundation; either *
38  * version 2.1 of the License, or (at your option) any later version. *
39  * *
40  * This library is distributed in the hope that it will be useful, *
41  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
42  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU *
43  * Lesser General Public License for more details. *
44  * *
45  * You should have received a copy of the GNU Lesser General Public *
46  * License along with this library; if not, write to the Free Software *
47  * Foundation, Inc., 59 Temple Place, *
48  * Suite 330, Boston, MA 02111-1307 USA *
49  * *
50  ***************************************************************************/
51 
52 #include <iostream>
53 #include <frames_io.hpp>
54 #include <models.hpp>
55 #include <chainiksolverpos_lma.hpp>
57 #include <utilities/utility.h>
58 
59 #include <boost/version.hpp>
60 #if BOOST_VERSION < 108300
61 #include <boost/timer.hpp>
62 #else
63 #include <boost/timer/timer.hpp>
64 #endif
65 
72 #if BOOST_VERSION < 108300
73  boost::timer timer;
74 #else
75  boost::timer::cpu_timer timer;
76 #endif
77  int num_of_trials = 1000000;
78  int total_number_of_iter = 0;
79  int n = chain.getNrOfJoints();
80  int nrofresult_ok = 0;
81  int nrofresult_minus1=0;
82  int nrofresult_minus2=0;
83  int nrofresult_minus3=0;
84  int min_num_of_iter = 10000000;
85  int max_num_of_iter = 0;
86  double min_diff = 1E10;
87  double max_diff = 0;
88  double min_trans_diff = 1E10;
89  double max_trans_diff = 0;
90  double min_rot_diff = 1E10;
91  double max_rot_diff = 0;
92  Eigen::Matrix<double,6,1> L;
93  L(0)=1;L(1)=1;L(2)=1;
94  L(3)=0.01;L(4)=0.01;L(5)=0.01;
95  KDL::ChainFkSolverPos_recursive fwdkin(chain);
96  KDL::ChainIkSolverPos_LMA solver(chain,L);
97  KDL::JntArray q(n);
98  KDL::JntArray q_init(n);
99  KDL::JntArray q_sol(n);
100  for (int trial=0;trial<num_of_trials;++trial) {
101  q.data.setRandom();
102  q.data *= KDL::PI;
103  q_init.data.setRandom();
104  q_init.data *= KDL::PI;
105  KDL::Frame pos_goal,pos_reached;
106  fwdkin.JntToCart(q,pos_goal);
107  //solver.compute_fwdpos(q.data);
108  //pos_goal = solver.T_base_head;
109  int retval;
110  retval = solver.CartToJnt(q_init,pos_goal,q_sol);
111  switch (retval) {
112  case 0:
113  nrofresult_ok++;
114  break;
115  case -1:
116  nrofresult_minus1++;
117  break;
118  case -2:
119  nrofresult_minus2++;
120  break;
121  case -3:
122  nrofresult_minus3++;
123  break;
124  }
125  if (retval !=0) {
126  std::cout << "-------------- failed ----------------------------" << std::endl;
127  std::cout << "pos " << pos_goal << std::endl;
128  std::cout << "reached pos " << solver.T_base_head << std::endl;
129  std::cout << "TF from pos to head \n" << pos_goal.Inverse()*solver.T_base_head << std::endl;
130  std::cout << "gradient " << solver.grad.transpose() << std::endl;
131  std::cout << "q " << q.data.transpose()/M_PI*180.0 << std::endl;
132  std::cout << "q_sol " << q_sol.data.transpose()/M_PI*180.0 << std::endl;
133  std::cout << "q_init " << q_init.data.transpose()/M_PI*180.0 << std::endl;
134  std::cout << "return value " << retval << std::endl;
135  std::cout << "last #iter " << solver.lastNrOfIter << std::endl;
136  std::cout << "last diff " << solver.lastDifference << std::endl;
137  std::cout << "jacobian of goal values ";
138  solver.display_jac(q);
139  std::cout << "jacobian of solved values ";
140  solver.display_jac(q_sol);
141  }
142  total_number_of_iter += solver.lastNrOfIter;
143  if (solver.lastNrOfIter > max_num_of_iter) max_num_of_iter = solver.lastNrOfIter;
144  if (solver.lastNrOfIter < min_num_of_iter) min_num_of_iter = solver.lastNrOfIter;
145  if (retval!=-3) {
146  if (solver.lastDifference > max_diff) max_diff = solver.lastDifference;
147  if (solver.lastDifference < min_diff) min_diff = solver.lastDifference;
148 
149  if (solver.lastTransDiff > max_trans_diff) max_trans_diff = solver.lastTransDiff;
150  if (solver.lastTransDiff < min_trans_diff) min_trans_diff = solver.lastTransDiff;
151 
152  if (solver.lastRotDiff > max_trans_diff) max_rot_diff = solver.lastRotDiff;
153  if (solver.lastRotDiff < min_trans_diff) min_rot_diff = solver.lastRotDiff;
154  }
155  fwdkin.JntToCart(q_sol,pos_reached);
156  }
157  std::cout << "------------------ statistics ------------------------------"<<std::endl;
158  std::cout << "#times successful " << nrofresult_ok << std::endl;
159  std::cout << "#times -1 result " << nrofresult_minus1 << std::endl;
160  std::cout << "#times -2 result " << nrofresult_minus2 << std::endl;
161  std::cout << "#times -3 result " << nrofresult_minus3 << std::endl;
162  std::cout << "average number of iter " << (double)total_number_of_iter/(double)num_of_trials << std::endl;
163  std::cout << "min. nr of iter " << min_num_of_iter << std::endl;
164  std::cout << "max. nr of iter " << max_num_of_iter << std::endl;
165  std::cout << "min. difference after solving " << min_diff << std::endl;
166  std::cout << "max. difference after solving " << max_diff << std::endl;
167  std::cout << "min. trans. difference after solving " << min_trans_diff << std::endl;
168  std::cout << "max. trans. difference after solving " << max_trans_diff << std::endl;
169  std::cout << "min. rot. difference after solving " << min_rot_diff << std::endl;
170  std::cout << "max. rot. difference after solving " << max_rot_diff << std::endl;
171 #if BOOST_VERSION < 108300
172  double el = timer.elapsed();
173 #else
174  boost::timer::cpu_times const ct(timer.elapsed());
175  double el = ct.user / 1e9;
176 #endif
177  std::cout << "elapsed time " << el << std::endl;
178  std::cout << "estimate of average time per invposkin (ms)" << el/num_of_trials*1000 << std::endl;
179  std::cout << "estimate of longest time per invposkin (ms) " << el/total_number_of_iter*max_num_of_iter *1000 << std::endl;
180  std::cout << "estimate of shortest time per invposkin (ms) " << el/total_number_of_iter*min_num_of_iter *1000 << std::endl;
181 }
182 
183 int main(int argc,char* argv[]) {
184  std::cout << " This example generates random joint positions, applies a forward kinematic transformation,\n"
185  << " and calls ChainIkSolverPos_LMA on the resulting pose. In this way we are sure that\n"
186  << " the resulting pose is reachable. However, some percentage of the trials will be at\n"
187  << " near singular position, where it is more difficult to achieve convergence and accuracy\n"
188  << " The initial position given to the algorithm is also a random joint position\n"
189  << " This routine asks for an accuracy of 10 micrometer, one order of magnitude better than a\n"
190  << " a typical industrial robot.\n"
191  << " This routine can take more then 6 minutes to execute. It then gives statistics on execution times\n"
192  << " and failures.\n"
193  << " Typically when executed 1 000 000 times, you will still see some small amount of failures\n"
194  << " Typically these failures are in the neighbourhood of singularities. Most failures of type -2 still\n"
195  << " reach an accuracy better than 1E-4.\n"
196  << " This is much better than ChainIkSolverPos_NR, which fails a few times per 100 trials.\n";
197 
198  KDL::Chain chain;
199  chain = KDL::Puma560();
200  //chain = KDL::KukaLWR_DHnew();
201 
202  KDL::ChainIkSolverPos_LMA solver(chain);
203 
204  test_inverseposkin(chain);
205 
206  return 0;
207 }
208 
KDL::Frame::Inverse
Frame Inverse() const
Gives back inverse transformation of a Frame.
Definition: frames.inl:422
KDL::JntArray
Definition: jntarray.hpp:69
KDL::ChainIkSolverPos_LMA::display_jac
void display_jac(const KDL::JntArray &jval)
for internal use only. Only exposed for test and diagnostic purposes.
Definition: chainiksolverpos_lma.cpp:200
frames_io.hpp
test_inverseposkin
void test_inverseposkin(KDL::Chain &chain)
Definition: chainiksolverpos_lma_demo.cpp:71
KDL::ChainIkSolverPos_LMA::T_base_head
KDL::Frame T_base_head
for internal use only.
Definition: chainiksolverpos_lma.hpp:256
chainfksolverpos_recursive.hpp
KDL::ChainIkSolverPos_LMA::lastRotDiff
double lastRotDiff
contains the last value for the (unweighted) rotational difference after an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:231
utility.h
iostream
std::cout
chainiksolverpos_lma.hpp
computing inverse position kinematics using Levenberg-Marquardt.
KDL::Frame
represents a frame transformation in 3D space (rotation + translation)
Definition: frames.hpp:572
KDL::PI
const double PI
the value of pi
Definition: utility.cxx:16
KDL::ChainFkSolverPos_recursive::JntToCart
virtual int JntToCart(const JntArray &q_in, Frame &p_out, int segmentNr=-1)
Definition: chainfksolverpos_recursive.cpp:34
KDL::Puma560
Chain Puma560()
Definition: puma560.cpp:27
KDL::JntArray::data
Eigen::VectorXd data
Definition: jntarray.hpp:72
std::endl
T endl(T... args)
main
int main(int argc, char *argv[])
Definition: chainiksolverpos_lma_demo.cpp:183
models.hpp
KDL::ChainIkSolverPos_LMA::lastTransDiff
double lastTransDiff
contains the last value for the (unweighted) translational difference after an execution of CartToJnt...
Definition: chainiksolverpos_lma.hpp:226
KDL::ChainIkSolverPos_LMA
Solver for the inverse position kinematics that uses Levenberg-Marquardt.
Definition: chainiksolverpos_lma.hpp:87
KDL::ChainIkSolverPos_LMA::lastDifference
double lastDifference
contains the last value for after an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:221
KDL::ChainIkSolverPos_LMA::grad
VectorXq grad
for internal use only.
Definition: chainiksolverpos_lma.hpp:250
KDL::ChainIkSolverPos_LMA::CartToJnt
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:210
KDL::ChainFkSolverPos_recursive
Definition: chainfksolverpos_recursive.hpp:36
KDL::Chain
This class encapsulates a serial kinematic interconnection structure. It is built out of segments.
Definition: chain.hpp:35
KDL::Chain::getNrOfJoints
unsigned int getNrOfJoints() const
Definition: chain.hpp:71
KDL::ChainIkSolverPos_LMA::lastNrOfIter
int lastNrOfIter
contains the last number of iterations for an execution of CartToJnt.
Definition: chainiksolverpos_lma.hpp:216