00001
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 #include "chainiksolverpos_lma.hpp"
00032 #include <iostream>
00033
00034 namespace KDL {
00035
00036
00037
00038
00039 template <typename Derived>
00040 inline void Twist_to_Eigen(const KDL::Twist& t,Eigen::MatrixBase<Derived>& e) {
00041 e(0)=t.vel.data[0];
00042 e(1)=t.vel.data[1];
00043 e(2)=t.vel.data[2];
00044 e(3)=t.rot.data[0];
00045 e(4)=t.rot.data[1];
00046 e(5)=t.rot.data[2];
00047 }
00048
00049
00050 ChainIkSolverPos_LMA::ChainIkSolverPos_LMA(
00051 const KDL::Chain& _chain,
00052 const Eigen::Matrix<double,6,1>& _L,
00053 double _eps,
00054 int _maxiter,
00055 double _eps_joints
00056 ) :
00057 chain(_chain),
00058 nj(chain.getNrOfJoints()),
00059 ns(chain.getNrOfSegments()),
00060 lastNrOfIter(0),
00061 lastDifference(0),
00062 lastTransDiff(0),
00063 lastRotDiff(0),
00064 lastSV(nj),
00065 jac(6, nj),
00066 grad(nj),
00067 display_information(false),
00068 maxiter(_maxiter),
00069 eps(_eps),
00070 eps_joints(_eps_joints),
00071 L(_L.cast<ScalarType>()),
00072 T_base_jointroot(nj),
00073 T_base_jointtip(nj),
00074 q(nj),
00075 A(nj, nj),
00076 tmp(nj),
00077 ldlt(nj),
00078 svd(6, nj,Eigen::ComputeThinU | Eigen::ComputeThinV),
00079 diffq(nj),
00080 q_new(nj),
00081 original_Aii(nj)
00082 {}
00083
00084 ChainIkSolverPos_LMA::ChainIkSolverPos_LMA(
00085 const KDL::Chain& _chain,
00086 double _eps,
00087 int _maxiter,
00088 double _eps_joints
00089 ) :
00090 chain(_chain),
00091 nj(chain.getNrOfJoints()),
00092 ns(chain.getNrOfSegments()),
00093 lastNrOfIter(0),
00094 lastDifference(0),
00095 lastTransDiff(0),
00096 lastRotDiff(0),
00097 lastSV(nj>6?6:nj),
00098 jac(6, nj),
00099 grad(nj),
00100 display_information(false),
00101 maxiter(_maxiter),
00102 eps(_eps),
00103 eps_joints(_eps_joints),
00104 T_base_jointroot(nj),
00105 T_base_jointtip(nj),
00106 q(nj),
00107 A(nj, nj),
00108 ldlt(nj),
00109 svd(6, nj,Eigen::ComputeThinU | Eigen::ComputeThinV),
00110 diffq(nj),
00111 q_new(nj),
00112 original_Aii(nj)
00113 {
00114 L(0)=1;
00115 L(1)=1;
00116 L(2)=1;
00117 L(3)=0.01;
00118 L(4)=0.01;
00119 L(5)=0.01;
00120 }
00121
00122 ChainIkSolverPos_LMA::~ChainIkSolverPos_LMA() {}
00123
00124 void ChainIkSolverPos_LMA::compute_fwdpos(const VectorXq& q) {
00125 using namespace KDL;
00126 unsigned int jointndx=0;
00127 T_base_head = Frame::Identity();
00128 for (unsigned int i=0;i<chain.getNrOfSegments();i++) {
00129 const Segment& segment = chain.getSegment(i);
00130 if (segment.getJoint().getType()!=Joint::None) {
00131 T_base_jointroot[jointndx] = T_base_head;
00132 T_base_head = T_base_head * segment.pose(q(jointndx));
00133 T_base_jointtip[jointndx] = T_base_head;
00134 jointndx++;
00135 } else {
00136 T_base_head = T_base_head * segment.pose(0.0);
00137 }
00138 }
00139 }
00140
00141 void ChainIkSolverPos_LMA::compute_jacobian(const VectorXq& q) {
00142 using namespace KDL;
00143 unsigned int jointndx=0;
00144 for (unsigned int i=0;i<chain.getNrOfSegments();i++) {
00145 const Segment& segment = chain.getSegment(i);
00146 if (segment.getJoint().getType()!=Joint::None) {
00147
00148 KDL::Twist t = ( T_base_jointroot[jointndx].M * segment.twist(q(jointndx),1.0) ).RefPoint( T_base_head.p - T_base_jointtip[jointndx].p);
00149 jac(0,jointndx)=t[0];
00150 jac(1,jointndx)=t[1];
00151 jac(2,jointndx)=t[2];
00152 jac(3,jointndx)=t[3];
00153 jac(4,jointndx)=t[4];
00154 jac(5,jointndx)=t[5];
00155 jointndx++;
00156 }
00157 }
00158 }
00159
00160 void ChainIkSolverPos_LMA::display_jac(const KDL::JntArray& jval) {
00161 VectorXq q;
00162 q = jval.data.cast<ScalarType>();
00163 compute_fwdpos(q);
00164 compute_jacobian(q);
00165 svd.compute(jac);
00166 std::cout << "Singular values : " << svd.singularValues().transpose()<<"\n";
00167 }
00168
00169
00170 int ChainIkSolverPos_LMA::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& T_base_goal, KDL::JntArray& q_out) {
00171 if(nj != q_init.rows() || nj != q_out.rows())
00172 return (error = E_SIZE_MISMATCH);
00173
00174 using namespace KDL;
00175 double v = 2;
00176 double tau = 10;
00177 double rho;
00178 double lambda;
00179 Twist t;
00180 double delta_pos_norm;
00181 Eigen::Matrix<ScalarType,6,1> delta_pos;
00182 Eigen::Matrix<ScalarType,6,1> delta_pos_new;
00183
00184
00185 q=q_init.data.cast<ScalarType>();
00186 compute_fwdpos(q);
00187 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
00188 delta_pos=L.asDiagonal()*delta_pos;
00189 delta_pos_norm = delta_pos.norm();
00190 if (delta_pos_norm<eps) {
00191 lastNrOfIter =0 ;
00192 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
00193 lastDifference = delta_pos.norm();
00194 lastTransDiff = delta_pos.topRows(3).norm();
00195 lastRotDiff = delta_pos.bottomRows(3).norm();
00196 svd.compute(jac);
00197 original_Aii = svd.singularValues();
00198 lastSV = svd.singularValues();
00199 q_out.data = q.cast<double>();
00200 return (error = E_NOERROR);
00201 }
00202 compute_jacobian(q);
00203 jac = L.asDiagonal()*jac;
00204
00205 lambda = tau;
00206 double dnorm = 1;
00207 for (unsigned int i=0;i<maxiter;++i) {
00208
00209 svd.compute(jac);
00210 original_Aii = svd.singularValues();
00211 for (unsigned int j=0;j<original_Aii.rows();++j) {
00212 original_Aii(j) = original_Aii(j)/( original_Aii(j)*original_Aii(j)+lambda);
00213
00214 }
00215 tmp = svd.matrixU().transpose()*delta_pos;
00216 tmp = original_Aii.cwiseProduct(tmp);
00217 diffq = svd.matrixV()*tmp;
00218 grad = jac.transpose()*delta_pos;
00219 if (display_information) {
00220 std::cout << "------- iteration " << i << " ----------------\n"
00221 << " q = " << q.transpose() << "\n"
00222 << " weighted jac = \n" << jac << "\n"
00223 << " lambda = " << lambda << "\n"
00224 << " eigenvalues = " << svd.singularValues().transpose() << "\n"
00225 << " difference = " << delta_pos.transpose() << "\n"
00226 << " difference norm= " << delta_pos_norm << "\n"
00227 << " proj. on grad. = " << grad << "\n";
00228 std::cout << std::endl;
00229 }
00230 dnorm = diffq.lpNorm<Eigen::Infinity>();
00231 if (dnorm < eps_joints) {
00232 lastDifference = delta_pos_norm;
00233 lastNrOfIter = i;
00234 lastSV = svd.singularValues();
00235 q_out.data = q.cast<double>();
00236 compute_fwdpos(q);
00237 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
00238 lastTransDiff = delta_pos.topRows(3).norm();
00239 lastRotDiff = delta_pos.bottomRows(3).norm();
00240 return (error = E_INCREMENT_JOINTS_TOO_SMALL);
00241 }
00242
00243
00244 if (grad.transpose()*grad < eps_joints*eps_joints ) {
00245 compute_fwdpos(q);
00246 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
00247 lastDifference = delta_pos_norm;
00248 lastTransDiff = delta_pos.topRows(3).norm();
00249 lastRotDiff = delta_pos.bottomRows(3).norm();
00250 lastSV = svd.singularValues();
00251 lastNrOfIter = i;
00252 q_out.data = q.cast<double>();
00253 return (error = E_GRADIENT_JOINTS_TOO_SMALL);
00254 }
00255
00256 q_new = q+diffq;
00257 compute_fwdpos(q_new);
00258 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos_new );
00259 delta_pos_new = L.asDiagonal()*delta_pos_new;
00260 double delta_pos_new_norm = delta_pos_new.norm();
00261 rho = delta_pos_norm*delta_pos_norm - delta_pos_new_norm*delta_pos_new_norm;
00262 rho /= diffq.transpose()*(lambda*diffq + grad);
00263 if (rho > 0) {
00264 q = q_new;
00265 delta_pos = delta_pos_new;
00266 delta_pos_norm = delta_pos_new_norm;
00267 if (delta_pos_norm<eps) {
00268 Twist_to_Eigen( diff( T_base_head, T_base_goal), delta_pos );
00269 lastDifference = delta_pos_norm;
00270 lastTransDiff = delta_pos.topRows(3).norm();
00271 lastRotDiff = delta_pos.bottomRows(3).norm();
00272 lastSV = svd.singularValues();
00273 lastNrOfIter = i;
00274 q_out.data = q.cast<double>();
00275 return (error = E_NOERROR);
00276 }
00277 compute_jacobian(q_new);
00278 jac = L.asDiagonal()*jac;
00279 double tmp=2*rho-1;
00280 lambda = lambda*max(1/3.0, 1-tmp*tmp*tmp);
00281 v = 2;
00282 } else {
00283 lambda = lambda*v;
00284 v = 2*v;
00285 }
00286 }
00287 lastDifference = delta_pos_norm;
00288 lastTransDiff = delta_pos.topRows(3).norm();
00289 lastRotDiff = delta_pos.bottomRows(3).norm();
00290 lastSV = svd.singularValues();
00291 lastNrOfIter = maxiter;
00292 q_out.data = q.cast<double>();
00293 return (error = E_MAX_ITERATIONS_EXCEEDED);
00294
00295 }
00296
00297 const char* ChainIkSolverPos_LMA::strError(const int error) const
00298 {
00299 if (E_GRADIENT_JOINTS_TOO_SMALL == error) return "The gradient of E towards the joints is to small";
00300 else if (E_INCREMENT_JOINTS_TOO_SMALL == error) return "The joint position increments are to small";
00301 else return SolverI::strError(error);
00302 }
00303
00304 };