JointPathEx.cpp
Go to the documentation of this file.
00001 #include "JointPathEx.h"
00002 #include <iostream>
00003 #include <iomanip>
00004 #include <limits.h>
00005 #include <float.h>
00006 #include <hrpUtil/MatrixSolvers.h>
00007 
00008 #define deg2rad(x)((x)*M_PI/180)
00009 #define rad2deg(rad) (rad * 180 / M_PI)
00010 #define eps_eq(a, b, c)  (fabs((a)-(b)) <= c)
00011 
00012 std::ostream& operator<<(std::ostream& out, hrp::dmatrix &a) {
00013     const int c = a.rows();
00014     const int n = a.cols();
00015 
00016     for(int i = 0; i < c; i++){
00017         out << "      :";
00018         for(int j = 0; j < n; j++){
00019             out << " " << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << (a)(i,j);
00020         }
00021         out << std::endl;
00022     }
00023     return out;
00024 }
00025 
00026 std::ostream& operator<<(std::ostream& out, hrp::dvector &a) {
00027     const int n = a.size();
00028 
00029     for(int i = 0; i < n; i++){
00030         out << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << a(i) << " ";
00031     }
00032     out << std::endl;
00033     return out;
00034 }
00035 
00036 //#define DEBUG true
00037 #define DEBUG false
00038 
00039 
00040 using namespace std;
00041 using namespace hrp;
00042 int hrp::calcSRInverse(const dmatrix& _a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w) {
00043     // J# = W Jt(J W Jt + kI)-1 (Weighted SR-Inverse)
00044     // SR-inverse :
00045     // Y. Nakamura and H. Hanafusa : "Inverse Kinematic Solutions With
00046     // Singularity Robustness for Robot Manipulator Control"
00047     // J. Dyn. Sys., Meas., Control  1986. vol 108, Issue 3, pp. 163--172.
00048 
00049     const int c = _a.rows(); // 6
00050     const int n = _a.cols(); // n
00051 
00052     if ( _w.cols() != n || _w.rows() != n ) {
00053         _w = dmatrix::Identity(n, n);
00054     }
00055 
00056     dmatrix at = _a.transpose();
00057     dmatrix a1(c, c);
00058     a1 = (_a * _w * at +  _sr_ratio * dmatrix::Identity(c,c)).inverse();
00059 
00060     //if (DEBUG) { dmatrix aat = _a * at; std::cerr << " a*at :" << std::endl << aat; }
00061 
00062     _a_sr  = _w * at * a1;
00063     //if (DEBUG) { dmatrix ii = _a * _a_sr; std::cerr << "    i :" << std::endl << ii; }
00064     return 0;
00065 }
00066 
00067 // overwrite hrplib/hrpUtil/Eigen3d.cpp
00068 Vector3 omegaFromRotEx(const Matrix33& r)
00069 {
00070     using ::std::numeric_limits;
00071 
00072     double alpha = (r(0,0) + r(1,1) + r(2,2) - 1.0) / 2.0;
00073 
00074     if(fabs(alpha - 1.0) < 1.0e-12) {   //th=0,2PI;
00075         return Vector3::Zero();
00076     } else {
00077         double th = acos(alpha);
00078         double s = sin(th);
00079 
00080         if (s < numeric_limits<double>::epsilon()) {   //th=PI
00081             return Vector3( sqrt((r(0,0)+1)*0.5)*th, sqrt((r(1,1)+1)*0.5)*th, sqrt((r(2,2)+1)*0.5)*th );
00082         }
00083 
00084         double k = -0.5 * th / s;
00085 
00086         return Vector3( (r(1,2) - r(2,1)) * k,
00087                         (r(2,0) - r(0,2)) * k,
00088                         (r(0,1) - r(1,0)) * k );
00089     }
00090 }
00091 
00092 JointPathEx::JointPathEx(BodyPtr& robot, Link* base, Link* end, double control_cycle, bool _use_inside_joint_weight_retrieval, const std::string& _debug_print_prefix)
00093     : JointPath(base, end), maxIKPosErrorSqr(1.0e-8), maxIKRotErrorSqr(1.0e-6), maxIKIteration(50), interlocking_joint_pair_indices(), sr_gain(1.0), manipulability_limit(0.1), manipulability_gain(0.001), dt(control_cycle),
00094       debug_print_prefix(_debug_print_prefix+",JointPathEx"), joint_limit_debug_print_counts(numJoints(), 0),
00095       debug_print_freq_count(static_cast<size_t>(0.25/dt)), // once per 0.25[s]
00096       use_inside_joint_weight_retrieval(_use_inside_joint_weight_retrieval) {
00097   for (unsigned int i = 0 ; i < numJoints(); i++ ) {
00098     joints.push_back(joint(i));
00099   }
00100   avoid_weight_gain.resize(numJoints());
00101   optional_weight_vector.resize(numJoints());
00102   for (unsigned int i = 0 ; i < numJoints(); i++ ) {
00103       optional_weight_vector[i] = 1.0;
00104   }
00105 }
00106 
00107 void JointPathEx::setMaxIKError(double epos, double erot) {
00108   maxIKPosErrorSqr = epos*epos;
00109   maxIKRotErrorSqr = erot*erot;
00110 }
00111 
00112 void JointPathEx::setMaxIKError(double e)
00113 {
00114     maxIKErrorSqr = e * e;
00115 }
00116 
00117 void JointPathEx::setMaxIKIteration(int iter) {
00118     maxIKIteration = iter;
00119 }
00120 
00121 bool JointPathEx::setInterlockingJointPairIndices (const std::vector<std::pair<Link*, Link*> >& pairs, const std::string& print_str) {
00122     // Convert pair<Link*, Link*> => pair<size_t, size_t>
00123     std::vector< std::pair<size_t, size_t> > tmp_vec;
00124     for (size_t i = 0; i < pairs.size(); i++) {
00125         std::pair<size_t, size_t> tmp_pair;
00126         bool is_first_ok = false, is_second_ok = false;
00127         for (size_t j = 0; j < joints.size(); j++) {
00128             if (joints[j]->name == pairs[i].first->name) {
00129                 tmp_pair.first = j;
00130                 is_first_ok = true;
00131             } else if (joints[j]->name == pairs[i].second->name) {
00132                 tmp_pair.second = j;
00133                 is_second_ok = true;
00134             }
00135         }
00136         if (is_first_ok && is_second_ok) tmp_vec.push_back(tmp_pair);
00137     }
00138     if (tmp_vec.size() > 0) {
00139         std::cerr << "[" << print_str << "]   Interlocking_joint_pair_indices is set => ";
00140         for (size_t j = 0; j < tmp_vec.size(); j++) {
00141             std::cerr << "[" << joints[tmp_vec[j].first]->name << ", " << joints[tmp_vec[j].second]->name << "] ";
00142         }
00143         std::cerr << std::endl;
00144         return setInterlockingJointPairIndices(tmp_vec);
00145     } else {
00146         std::cerr << "[" << print_str << "]   No interlocking_joint_pair_indices set." << std::endl;
00147         return false;
00148     }
00149 };
00150 
00151 bool JointPathEx::setInterlockingJointPairIndices (const std::vector<std::pair<size_t, size_t> >& pairs) {
00152     interlocking_joint_pair_indices = pairs;
00153     return true;
00154 };
00155 
00156 void JointPathEx::getInterlockingJointPairIndices (std::vector<std::pair<size_t, size_t> >& pairs) {
00157     pairs = interlocking_joint_pair_indices;
00158 };
00159 
00160 bool JointPathEx::calcJacobianInverseNullspace(dmatrix &J, dmatrix &Jinv, dmatrix &Jnull) {
00161     const int n = numJoints();
00162                 
00163     hrp::dmatrix w = hrp::dmatrix::Identity(n,n);
00164     //
00165     // wmat/weight: weighting joint angle weight
00166     //
00167     // w_i = 1 + | dH/dt |      if d|dH/dt| >= 0
00168     //     = 1                  if d|dH/dt| <  0
00169     // dH/dt = (t_max - t_min)^2 (2t - t_max - t_min)
00170     //         / 4 (t_max - t)^2 (t - t_min)^2
00171     //
00172     // T. F. Chang and R.-V. Dubey: "A weighted least-norm solution based
00173     // scheme for avoiding joint limits for redundant manipulators", in IEEE
00174     // Trans. On Robotics and Automation, 11((2):286-292, April 1995.
00175     //
00176     for ( int j = 0; j < n ; j++ ) {
00177         double jang = joints[j]->q;
00178         double jmax = joints[j]->ulimit;
00179         double jmin = joints[j]->llimit;
00180         double e = deg2rad(1);
00181         if ( eps_eq(jang, jmax,e) && eps_eq(jang, jmin,e) ) {
00182         } else if ( eps_eq(jang, jmax,e) ) {
00183             jang = jmax - e;
00184         } else if ( eps_eq(jang, jmin,e) ) {
00185             jang = jmin + e;
00186         }
00187 
00188         double r;
00189         if ( eps_eq(jang, jmax,e) && eps_eq(jang, jmin,e) ) {
00190             r = DBL_MAX;
00191         } else {
00192             r = fabs( (pow((jmax - jmin),2) * (( 2 * jang) - jmax - jmin)) /
00193                       (4 * pow((jmax - jang),2) * pow((jang - jmin),2)) );
00194             if (std::isnan(r)) r = 0;
00195         }
00196 
00197         // If use_inside_joint_weight_retrieval = true (true by default), use T. F. Chang and R.-V. Dubeby weight retrieval inward.
00198         // Otherwise, joint weight is always calculated from limit value to resolve https://github.com/fkanehiro/hrpsys-base/issues/516.
00199         if (( r - avoid_weight_gain[j] ) >= 0 ) {
00200           w(j, j) = optional_weight_vector[j] * ( 1.0 / ( 1.0 + r) );
00201         } else {
00202             if (use_inside_joint_weight_retrieval)
00203                 w(j, j) = optional_weight_vector[j] * 1.0;
00204             else
00205                 w(j, j) = optional_weight_vector[j] * ( 1.0 / ( 1.0 + r) );
00206         }
00207         avoid_weight_gain[j] = r;
00208     }
00209     if ( DEBUG ) {
00210         std::cerr << " cost :";
00211         for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << avoid_weight_gain[j]; }
00212         std::cerr << std::endl;
00213         std::cerr << " optw :";
00214         for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << optional_weight_vector[j]; }
00215         std::cerr << std::endl;
00216         std::cerr << "    w :";
00217         for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << w(j, j); }
00218         std::cerr << std::endl;
00219     }
00220 
00221     double manipulability = sqrt((J*J.transpose()).determinant());
00222     double k = 0;
00223     if ( manipulability < manipulability_limit ) {
00224         k = manipulability_gain * pow((1 - ( manipulability / manipulability_limit )), 2);
00225     }
00226     if ( DEBUG ) {
00227         std::cerr << " manipulability = " <<  manipulability << " < " << manipulability_limit << ", k = " << k << " -> " << sr_gain * k << std::endl;
00228     }
00229 
00230     calcSRInverse(J, Jinv, sr_gain * k, w);
00231 
00232     Jnull = ( hrp::dmatrix::Identity(n, n) - Jinv * J);
00233 
00234     return true;
00235 }
00236 
00237 bool JointPathEx::calcInverseKinematics2Loop(const Vector3& dp, const Vector3& omega,
00238                                              const double LAMBDA, const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q) {
00239     const int n = numJoints();
00240 
00241     if ( DEBUG ) {
00242         std::cerr << "angle :";
00243         for(int j=0; j < n; ++j){
00244             std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(joints[j]->q);
00245         }
00246         std::cerr << endl;
00247     }
00248 
00249     size_t ee_workspace_dim = 6; // End-effector workspace dimensions including pos(3) and rot(3)
00250     size_t ij_workspace_dim = interlocking_joint_pair_indices.size(); // Dimensions for interlocking joints constraint. 0 by default.
00251     size_t workspace_dim = ee_workspace_dim + ij_workspace_dim;
00252 
00253     // Total jacobian, workspace velocty, and so on
00254     hrp::dmatrix J(workspace_dim, n);
00255     dvector v(workspace_dim);
00256     hrp::dmatrix Jinv(n, workspace_dim);
00257     hrp::dmatrix Jnull(n, n);
00258     hrp::dvector dq(n);
00259 
00260     if (ij_workspace_dim > 0) {
00261         v << dp, omega, dvector::Zero(ij_workspace_dim);
00262         hrp::dmatrix ee_J = dmatrix::Zero(ee_workspace_dim, n);
00263         calcJacobian(ee_J);
00264         hrp::dmatrix ij_J = dmatrix::Zero(ij_workspace_dim, n);
00265         for (size_t i = 0; i < ij_workspace_dim; i++) {
00266             std::pair<size_t, size_t>& pair = interlocking_joint_pair_indices[i];
00267             ij_J(i, pair.first) = 1;
00268             ij_J(i, pair.second) = -1;
00269         }
00270         J << ee_J, ij_J;
00271     } else {
00272         v << dp, omega;
00273         calcJacobian(J);
00274     }
00275     calcJacobianInverseNullspace(J, Jinv, Jnull);
00276     dq = Jinv * v; // dq = pseudoInverse(J) * v
00277 
00278     if ( DEBUG ) {
00279         std::cerr << "    v :";
00280         for(int j=0; j < v.size(); ++j){
00281             std::cerr << " " << v(j);
00282         }
00283         std::cerr << std::endl;
00284         std::cerr << "    J :" << std::endl << J;
00285         std::cerr << " Jinv :" << std::endl << Jinv;
00286     }
00287     // If avoid_gain is set, add joint limit avoidance by null space vector
00288     if ( avoid_gain > 0.0 ) {
00289       // dq = J#t a dx + ( I - J# J ) Jt b dx
00290       // avoid-nspace-joint-limit: avoiding joint angle limit
00291       //
00292       // dH/dq = (((t_max + t_min)/2 - t) / ((t_max - t_min)/2)) ^2
00293       hrp::dvector u(n);
00294       for ( int j = 0; j < n ; j++ ) {
00295         double jang = joint(j)->q;
00296         double jmax = joint(j)->ulimit;
00297         double jmin = joint(j)->llimit;
00298         double r = ((( (jmax + jmin) / 2.0) - jang) / ((jmax - jmin) / 2.0));
00299         if ( r > 0 ) { r = r*r; } else { r = - r*r; }
00300         u[j] = optional_weight_vector[j] * avoid_gain * r;
00301       }
00302       if ( DEBUG ) {
00303         std::cerr << " u(jl):";
00304         for(int j=0; j < n; ++j){
00305           std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(u(j));
00306         }
00307         std::cerr << std::endl;
00308         std::cerr << " JN*u :";
00309         hrp::dvector Jnullu = Jnull * u;
00310         for(int j=0; j < n; ++j){
00311           std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(Jnullu(j));
00312         }
00313         std::cerr << std::endl;
00314       }
00315       dq = dq + Jnull * u;
00316     }
00317     // If reference_gain and reference_q are set, add following to reference_q by null space vector
00318     if ( reference_gain > 0.0 && reference_q != NULL ) {
00319       //
00320       // qref - qcurr
00321       hrp::dvector u(n);
00322       for ( unsigned int j = 0; j < numJoints(); j++ ) {
00323         u[j] = optional_weight_vector[j] * reference_gain * ( (*reference_q)[joint(j)->jointId] - joint(j)->q );
00324       }
00325       if ( DEBUG ) {
00326         std::cerr << "u(ref):";
00327         for(int j=0; j < n; ++j){
00328           std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(u(j));
00329         }
00330         std::cerr << std::endl;
00331         std::cerr << "  JN*u:";
00332         hrp::dvector nullu = Jnull * u;
00333         for(int j=0; j < n; ++j){
00334           std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(nullu(j));
00335         }
00336         std::cerr << std::endl;
00337       }
00338       dq = dq + Jnull * u;
00339     }
00340     if ( DEBUG ) {
00341       std::cerr << "   dq :";
00342       for(int j=0; j < n; ++j){
00343         std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(dq(j));
00344       }
00345       std::cerr << std::endl;
00346     }
00347 
00348     // dq limitation using lvlimit/uvlimit
00349     double min_speed_ratio = 1.0;
00350     for(int j=0; j < n; ++j){
00351         double speed_ratio = 1.0;
00352         if (dq(j) < joints[j]->lvlimit * dt) {
00353             speed_ratio = fabs(joints[j]->lvlimit * dt / dq(j));
00354         } else if (dq(j) > joints[j]->uvlimit * dt) {
00355             speed_ratio = fabs(joints[j]->uvlimit * dt / dq(j));
00356         }
00357         min_speed_ratio = std::max(std::min(min_speed_ratio, speed_ratio), 0.0);
00358     }
00359     if ( min_speed_ratio < 1.0 ) { 
00360       if ( DEBUG ) {
00361         std::cerr << "spdlmt: ";
00362         for(int j=0; j < n; ++j) { std::cerr << dq(j) << " "; } std::cerr << std::endl;
00363       }
00364       for(int j=0; j < n; ++j) {
00365         dq(j) = dq(j) * min_speed_ratio; // make
00366       }
00367       if ( DEBUG ) {
00368         std::cerr << "spdlmt: ";
00369         for(int j=0; j < n; ++j) { std::cerr << dq(j) << " "; } std::cerr << std::endl;
00370       }
00371     }
00372 
00373     // check nan / inf
00374     bool solve_linear_equation = true;
00375     for(int j=0; j < n; ++j){
00376       if ( std::isnan(dq(j)) || std::isinf(dq(j)) ) {
00377         solve_linear_equation = false;
00378         break;
00379       }
00380     }
00381     if ( ! solve_linear_equation ) {
00382       std::cerr << "[" << debug_print_prefix << "] ERROR nan/inf is found" << std::endl;
00383       return false;
00384     }
00385 
00386     // joint angles update
00387     for(int j=0; j < n; ++j){
00388       joints[j]->q += LAMBDA * dq(j);
00389     }
00390 
00391     // If interlocking joints are defined, set interlocking joints by mid point
00392     for (size_t i = 0; i < interlocking_joint_pair_indices.size(); i++) {
00393         std::pair<size_t, size_t>& pair = interlocking_joint_pair_indices[i];
00394         double midp = (joints[pair.first]->q + joints[pair.second]->q)/2.0;
00395         joints[pair.first]->q = midp;
00396         joints[pair.second]->q = midp;
00397     }
00398 
00399     // upper/lower limit check
00400     for(int j=0; j < n; ++j){
00401       bool is_limit_over = false;
00402       if ( joints[j]->q > joints[j]->ulimit) {
00403         is_limit_over = true;
00404         if (joint_limit_debug_print_counts[j] % debug_print_freq_count == 0) {
00405             std::cerr << "[" << debug_print_prefix << "] Upper joint limit over " << joints[j]->name
00406                       << " (ja=" << joints[j]->q << "[rad], limit=" << joints[j]->ulimit << "[rad], count=" << joint_limit_debug_print_counts[j] << ", debug_print_freq_count=" << debug_print_freq_count << ")" << std::endl;
00407         }
00408         joints[j]->q = joints[j]->ulimit;
00409       }
00410       if ( joints[j]->q < joints[j]->llimit) {
00411         is_limit_over = true;
00412         if (joint_limit_debug_print_counts[j] % debug_print_freq_count == 0) {
00413             std::cerr << "[" << debug_print_prefix << "] Lower joint limit over " << joints[j]->name
00414                       << " (ja=" << joints[j]->q << "[rad], limit=" << joints[j]->llimit << "[rad], count=" << joint_limit_debug_print_counts[j] << ", debug_print_freq_count=" << debug_print_freq_count << ")" << std::endl;
00415         }
00416         joints[j]->q = joints[j]->llimit;
00417       }
00418       joints[j]->q = std::max(joints[j]->q, joints[j]->llimit);
00419       if (is_limit_over) {
00420           joint_limit_debug_print_counts[j]++;
00421       } else {
00422           joint_limit_debug_print_counts[j] = 0; // resetting
00423       }
00424     }
00425 
00426     calcForwardKinematics();
00427 
00428     return true;
00429 }
00430 
00431 // TODO : matrix_logEx should be omegaFromRotEx after checking on real robot testing.
00432 hrp::Vector3 matrix_logEx(const hrp::Matrix33& m) {
00433     hrp::Vector3 mlog;
00434     double q0, th;
00435     hrp::Vector3 q;
00436     double norm;
00437   
00438     Eigen::Quaternion<double> eiq(m);
00439     q0 = eiq.w();
00440     q = eiq.vec();
00441     norm = q.norm();
00442     if (norm > 0) {
00443         if ((q0 > 1.0e-10) || (q0 < -1.0e-10)) {
00444             th = 2 * std::atan(norm / q0);
00445         } else if (q0 > 0) {
00446             th = M_PI / 2;
00447         } else {
00448             th = -M_PI / 2;
00449         }
00450         mlog = (th / norm) * q ;
00451     } else {
00452         mlog = hrp::Vector3::Zero();
00453     }
00454     return mlog;
00455 }
00456 
00457 bool JointPathEx::calcInverseKinematics2Loop(const Vector3& end_effector_p, const Matrix33& end_effector_R,
00458                                              const double LAMBDA, const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q,
00459                                              const double vel_gain,
00460                                              const hrp::Vector3& localPos, const hrp::Matrix33& localR)
00461 {
00462     hrp::Matrix33 target_link_R(end_effector_R * localR.transpose());
00463     hrp::Vector3 target_link_p(end_effector_p - target_link_R * localPos);
00464     hrp::Vector3 vel_p(target_link_p - endLink()->p);
00465     // TODO : matrix_logEx should be omegaFromRotEx after checking on real robot testing.
00466     //hrp::Vector3 vel_r(endLink()->R * omegaFromRotEx(endLink()->R.transpose() * target_link_R));
00467     hrp::Vector3 vel_r(endLink()->R * matrix_logEx(endLink()->R.transpose() * target_link_R));
00468     vel_p *= vel_gain;
00469     vel_r *= vel_gain;
00470     return calcInverseKinematics2Loop(vel_p, vel_r, LAMBDA, avoid_gain, reference_gain, reference_q);
00471 }
00472 
00473 bool JointPathEx::calcInverseKinematics2(const Vector3& end_p, const Matrix33& end_R,
00474                                          const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q)
00475 {
00476     static const int MAX_IK_ITERATION = maxIKIteration;
00477     static const double LAMBDA = 0.9;
00478 
00479     LinkPath linkPath(baseLink(), endLink());
00480 
00481     if(joints.empty()){
00482         if(linkPath.empty()){
00483             return false;
00484         }
00485         if(baseLink() == endLink()){
00486             baseLink()->p = end_p;
00487             baseLink()->R = end_R;
00488             return true;
00489         } else {
00490             // \todo implement here
00491             return false;
00492         }
00493     }
00494     
00495     const int n = numJoints();
00496     dvector qorg(n);
00497 
00498     Link* target = linkPath.endLink();
00499 
00500     for(int i=0; i < n; ++i){
00501         qorg[i] = joints[i]->q;
00502         avoid_weight_gain[i] = 100000000000000000000.0;
00503     }
00504 
00505     
00506     double errsqr = DBL_MAX;//maxIKErrorSqr * 100.0;
00507     double errsqr0 = errsqr;
00508     bool converged = false;
00509 
00510     int iter = 0;
00511     for(iter = 0; iter < MAX_IK_ITERATION; iter++){
00512         
00513       if ( DEBUG ) {
00514         std::cerr << " iter : " << iter << " / " << MAX_IK_ITERATION << ", n = " << n << std::endl;
00515       }
00516         
00517       Vector3 dp(end_p - target->p);
00518       Vector3 omega(target->R * omegaFromRotEx(target->R.transpose() * end_R));
00519       if ( dp.norm() > 0.1 ) dp = dp*0.1/dp.norm();
00520       if ( omega.norm() > 0.5 ) omega = omega*0.5/omega.norm();
00521 
00522 
00523       if ( DEBUG ) {
00524         std::cerr << "   dp : " << dp[0] << " " << dp[1] << " " << dp[2] << std::endl;
00525         std::cerr << "omega : " << omega[0] << " " << omega[1] << " " << omega[2] << std::endl;
00526         //std::cerr << "    J :" << std::endl << J;
00527         //std::cerr << "  det : " << det(J) << std::endl;
00528         std::cerr << "  err : dp = " << dp.dot(dp) << ", omega = " <<  omega.dot(omega) << std::endl;
00529       }
00530 
00531       if(isBestEffortIKMode){
00532         errsqr0 = errsqr;
00533         errsqr = dp.dot(dp) + omega.dot(omega);
00534         if ( DEBUG ) std::cerr << "  err : fabs(" << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << errsqr << " - " << errsqr0 << ") = " << fabs(errsqr-errsqr0) << " < " << maxIKErrorSqr << " BestEffortIKMode" << std::endl;
00535         if(fabs(errsqr - errsqr0) < maxIKErrorSqr){
00536           converged = true;
00537           break;
00538         }
00539       } else {
00540         if ( DEBUG ) std::cerr << "  err : " << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << sqrt(dp.dot(dp)) << " < " << sqrt(maxIKPosErrorSqr) << ", " << std::setw(18) << std::setiosflags(std::ios::fixed) << std::setprecision(14) << sqrt(omega.dot(omega)) << " < " << sqrt(maxIKRotErrorSqr) << std::endl;
00541         if( (dp.dot(dp) < maxIKPosErrorSqr) && (omega.dot(omega) < maxIKRotErrorSqr) ) {
00542           converged = true;
00543           break;
00544         }
00545       }
00546 
00547       if ( !calcInverseKinematics2Loop(dp, omega, LAMBDA, avoid_gain, reference_gain, reference_q) )
00548         return false;
00549     }
00550 
00551     if(!converged){
00552       std::cerr << "IK Fail, iter = " << iter << std::endl;
00553       Vector3 dp(end_p - target->p);
00554       Vector3 omega(target->R * omegaFromRotEx(target->R.transpose() * end_R));
00555       const double errsqr = dp.dot(dp) + omega.dot(omega);
00556       if(isBestEffortIKMode){
00557         std::cerr << "  err : fabs(" << errsqr << " - " << errsqr0 << ") = " << fabs(errsqr-errsqr0) << " < " << maxIKErrorSqr << " BestEffortIKMode" << std::endl;
00558       } else {
00559           std::cerr << "  err : " << dp.dot(dp) << " ( " << dp[0] << " " << dp[1] << " " << dp[2] << ") < " << maxIKPosErrorSqr << std::endl;
00560           std::cerr << "      : " << omega.dot(omega) << " ( " << omega[0] << " " << omega[1] << " " << omega[2] << ") < " << maxIKRotErrorSqr << std::endl;
00561       }
00562       for(int i=0; i < n; ++i){
00563         joints[i]->q = qorg[i];
00564       }
00565       calcForwardKinematics();
00566     }
00567     
00568     return converged;
00569 }
00570 
00571 void hrp::readVirtualForceSensorParamFromProperties (std::map<std::string, hrp::VirtualForceSensorParam>& vfs,
00572                                                      hrp::BodyPtr m_robot,
00573                                                      const std::string& prop_string,
00574                                                      const std::string& instance_name)
00575 {
00576     coil::vstring virtual_force_sensor = coil::split(prop_string, ",");
00577     unsigned int nvforce = virtual_force_sensor.size()/10;
00578     for (unsigned int i=0; i<nvforce; i++){
00579         std::string name = virtual_force_sensor[i*10+0];
00580         hrp::dvector tr(7);
00581         for (int j = 0; j < 7; j++ ) {
00582           coil::stringTo(tr[j], virtual_force_sensor[i*10+3+j].c_str());
00583         }
00584         vfs.insert(std::pair<std::string, VirtualForceSensorParam>(name, VirtualForceSensorParam()));
00585         VirtualForceSensorParam& p = vfs[name];
00586         p.localPos = hrp::Vector3(tr[0], tr[1], tr[2]);
00587         p.localR = Eigen::AngleAxis<double>(tr[6], hrp::Vector3(tr[3],tr[4],tr[5])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
00588         p.link = m_robot->link(virtual_force_sensor[i*10+2]);
00589         p.id = i;
00590         std::cerr << "[" << instance_name << "] virtual force sensor" << std::endl;
00591         std::cerr << "[" << instance_name << "]   name = " << name << ", parent = " << p.link->name << ", id = " << p.id << std::endl;
00592         std::cerr << "[" << instance_name << "]   localP = " << p.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[m]" << std::endl;
00593         std::cerr << "[" << instance_name << "]   localR = " << p.localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", "    [", "]")) << std::endl;
00594     }
00595 };
00596 
00597 void hrp::readInterlockingJointsParamFromProperties (std::vector<std::pair<Link*, Link*> >& pairs,
00598                                                      hrp::BodyPtr m_robot,
00599                                                      const std::string& prop_string,
00600                                                      const std::string& instance_name)
00601 {
00602     coil::vstring interlocking_joints_str = coil::split(prop_string, ",");
00603     size_t ij_prop_num = 2;
00604     if (interlocking_joints_str.size() > 0) {
00605         size_t num = interlocking_joints_str.size()/ij_prop_num;
00606         for (size_t i = 0; i < num; i++) {
00607             //std::cerr << "[" << instance_name << "] Interlocking Joints [" << interlocking_joints_str[i*ij_prop_num] << "], [" << interlocking_joints_str[i*ij_prop_num+1] << "]" << std::endl;
00608             hrp::Link* link1 = m_robot->link(interlocking_joints_str[i*ij_prop_num]);
00609             hrp::Link* link2 = m_robot->link(interlocking_joints_str[i*ij_prop_num+1]);
00610             if (link1 == NULL || link2 == NULL) {
00611                 std::cerr << "[" << instance_name << "] No such interlocking joints [" << interlocking_joints_str[i*ij_prop_num] << "], [" << interlocking_joints_str[i*ij_prop_num+1] << "]" << std::endl;
00612                 continue;
00613             }
00614             std::pair<hrp::Link*, hrp::Link*> pair(link1, link2);
00615             pairs.push_back(pair);
00616         };
00617     }
00618 };
00619 
00620 void hrp::calcAccelerationsForInverseDynamics(const hrp::BodyPtr _m_robot, InvDynStateBuffer& _idsb){
00621   for(int i=0;i<_m_robot->numJoints();i++)_idsb.q(i) = _m_robot->joint(i)->q;
00622   _idsb.dq = (_idsb.q - _idsb.q_old) / _idsb.DT;
00623   _idsb.ddq = (_idsb.q - 2 * _idsb.q_old + _idsb.q_oldold) / (_idsb.DT * _idsb.DT);
00624   const hrp::Vector3 g(0, 0, 9.80665);
00625   _idsb.base_p = _m_robot->rootLink()->p;
00626   _idsb.base_v = (_idsb.base_p - _idsb.base_p_old) / _idsb.DT;
00627   _idsb.base_dv = g + (_idsb.base_p - 2 * _idsb.base_p_old + _idsb.base_p_oldold) / (_idsb.DT * _idsb.DT);
00628   _idsb.base_R =  _m_robot->rootLink()->R;
00629   _idsb.base_dR = (_idsb.base_R - _idsb.base_R_old) / _idsb.DT;
00630   _idsb.base_w_hat = _idsb.base_dR * _idsb.base_R.transpose();
00631   _idsb.base_w = hrp::Vector3(_idsb.base_w_hat(2,1), - _idsb.base_w_hat(0,2), _idsb.base_w_hat(1,0));
00632   _idsb.base_dw = (_idsb.base_w - _idsb.base_w_old) / _idsb.DT;
00633 };
00634 
00635 void hrp::calcRootLinkWrenchFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer& _idsb, hrp::Vector3& _f_ans, hrp::Vector3& _t_ans){
00636   for(int i=0;i<_m_robot->numJoints();i++){
00637     _m_robot->joint(i)->dq = _idsb.dq(i);
00638     _m_robot->joint(i)->ddq = _idsb.ddq(i);
00639   }
00640   _m_robot->rootLink()->vo = _idsb.base_v - _idsb.base_w.cross(_idsb.base_p);
00641   _m_robot->rootLink()->dvo = _idsb.base_dv - _idsb.base_dw.cross(_idsb.base_p) - _idsb.base_w.cross(_idsb.base_v); // calc in differential way
00642   _m_robot->rootLink()->w = _idsb.base_w;
00643   _m_robot->rootLink()->dw = _idsb.base_dw;
00644   _m_robot->calcForwardKinematics(true,true);// calc every link's acc and vel
00645   _m_robot->calcInverseDynamics(_m_robot->rootLink(), _f_ans, _t_ans);// this returns f,t at the coordinate origin (not at base link pos)
00646 };
00647 
00648 void hrp::calcWorldZMPFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer& _idsb, hrp::Vector3& _zmp_ans){
00649   hrp::Vector3 f_tmp, t_tmp;
00650   calcRootLinkWrenchFromInverseDynamics(_m_robot, _idsb, f_tmp, t_tmp);
00651   _zmp_ans(0) = -t_tmp(1)/f_tmp(2);
00652   _zmp_ans(1) = t_tmp(0)/f_tmp(2);
00653 };
00654 
00655 void hrp::updateInvDynStateBuffer(InvDynStateBuffer& _idsb){
00656    _idsb.q_oldold = _idsb.q_old;
00657    _idsb.q_old = _idsb.q;
00658    _idsb.base_p_oldold = _idsb.base_p_old;
00659    _idsb.base_p_old = _idsb.base_p;
00660    _idsb.base_R_old = _idsb.base_R;
00661    _idsb.base_w_old = _idsb.base_w;
00662 };


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:18