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


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed Sep 6 2017 02:35:55