JointPathEx.cpp
Go to the documentation of this file.
1 #include "JointPathEx.h"
2 #include <iostream>
3 #include <iomanip>
4 #include <limits.h>
5 #include <float.h>
7 
8 #define deg2rad(x)((x)*M_PI/180)
9 #define rad2deg(rad) (rad * 180 / M_PI)
10 #define eps_eq(a, b, c) (fabs((a)-(b)) <= c)
11 
12 std::ostream& operator<<(std::ostream& out, hrp::dmatrix &a) {
13  const int c = a.rows();
14  const int n = a.cols();
15 
16  for(int i = 0; i < c; i++){
17  out << " :";
18  for(int j = 0; j < n; j++){
19  out << " " << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << (a)(i,j);
20  }
21  out << std::endl;
22  }
23  return out;
24 }
25 
26 std::ostream& operator<<(std::ostream& out, hrp::dvector &a) {
27  const int n = a.size();
28 
29  for(int i = 0; i < n; i++){
30  out << std::setw(7) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << a(i) << " ";
31  }
32  out << std::endl;
33  return out;
34 }
35 
36 //#define DEBUG true
37 #define DEBUG false
38 
39 
40 using namespace std;
41 using namespace hrp;
42 int hrp::calcSRInverse(const dmatrix& _a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w) {
43  // J# = W Jt(J W Jt + kI)-1 (Weighted SR-Inverse)
44  // SR-inverse :
45  // Y. Nakamura and H. Hanafusa : "Inverse Kinematic Solutions With
46  // Singularity Robustness for Robot Manipulator Control"
47  // J. Dyn. Sys., Meas., Control 1986. vol 108, Issue 3, pp. 163--172.
48 
49  const int c = _a.rows(); // 6
50  const int n = _a.cols(); // n
51 
52  if ( _w.cols() != n || _w.rows() != n ) {
53  _w = dmatrix::Identity(n, n);
54  }
55 
56  dmatrix at = _a.transpose();
57  dmatrix a1(c, c);
58  a1 = (_a * _w * at + _sr_ratio * dmatrix::Identity(c,c)).inverse();
59 
60  //if (DEBUG) { dmatrix aat = _a * at; std::cerr << " a*at :" << std::endl << aat; }
61 
62  _a_sr = _w * at * a1;
63  //if (DEBUG) { dmatrix ii = _a * _a_sr; std::cerr << " i :" << std::endl << ii; }
64  return 0;
65 }
66 
67 // overwrite hrplib/hrpUtil/Eigen3d.cpp
69 {
70  using ::std::numeric_limits;
71 
72  double alpha = (r(0,0) + r(1,1) + r(2,2) - 1.0) / 2.0;
73 
74  if(fabs(alpha - 1.0) < 1.0e-12) { //th=0,2PI;
75  return Vector3::Zero();
76  } else {
77  double th = acos(alpha);
78  double s = sin(th);
79 
80  if (s < numeric_limits<double>::epsilon()) { //th=PI
81  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 );
82  }
83 
84  double k = -0.5 * th / s;
85 
86  return Vector3( (r(1,2) - r(2,1)) * k,
87  (r(2,0) - r(0,2)) * k,
88  (r(0,1) - r(1,0)) * k );
89  }
90 }
91 
92 JointPathEx::JointPathEx(BodyPtr& robot, Link* base, Link* end, double control_cycle, bool _use_inside_joint_weight_retrieval, const std::string& _debug_print_prefix)
93  : 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),
94  debug_print_prefix(_debug_print_prefix+",JointPathEx"), joint_limit_debug_print_counts(numJoints(), 0),
95  debug_print_freq_count(static_cast<size_t>(0.25/dt)), // once per 0.25[s]
96  use_inside_joint_weight_retrieval(_use_inside_joint_weight_retrieval) {
97  for (unsigned int i = 0 ; i < numJoints(); i++ ) {
98  joints.push_back(joint(i));
99  }
100  avoid_weight_gain.resize(numJoints());
102  for (unsigned int i = 0 ; i < numJoints(); i++ ) {
103  optional_weight_vector[i] = 1.0;
104  }
105 }
106 
107 void JointPathEx::setMaxIKError(double epos, double erot) {
108  maxIKPosErrorSqr = epos*epos;
109  maxIKRotErrorSqr = erot*erot;
110 }
111 
113 {
114  maxIKErrorSqr = e * e;
115 }
116 
118  maxIKIteration = iter;
119 }
120 
121 bool JointPathEx::setInterlockingJointPairIndices (const std::vector<std::pair<Link*, Link*> >& pairs, const std::string& print_str) {
122  // Convert pair<Link*, Link*> => pair<size_t, size_t>
123  std::vector< std::pair<size_t, size_t> > tmp_vec;
124  for (size_t i = 0; i < pairs.size(); i++) {
125  std::pair<size_t, size_t> tmp_pair;
126  bool is_first_ok = false, is_second_ok = false;
127  for (size_t j = 0; j < joints.size(); j++) {
128  if (joints[j]->name == pairs[i].first->name) {
129  tmp_pair.first = j;
130  is_first_ok = true;
131  } else if (joints[j]->name == pairs[i].second->name) {
132  tmp_pair.second = j;
133  is_second_ok = true;
134  }
135  }
136  if (is_first_ok && is_second_ok) tmp_vec.push_back(tmp_pair);
137  }
138  if (tmp_vec.size() > 0) {
139  std::cerr << "[" << print_str << "] Interlocking_joint_pair_indices is set => ";
140  for (size_t j = 0; j < tmp_vec.size(); j++) {
141  std::cerr << "[" << joints[tmp_vec[j].first]->name << ", " << joints[tmp_vec[j].second]->name << "] ";
142  }
143  std::cerr << std::endl;
144  return setInterlockingJointPairIndices(tmp_vec);
145  } else {
146  std::cerr << "[" << print_str << "] No interlocking_joint_pair_indices set." << std::endl;
147  return false;
148  }
149 };
150 
151 bool JointPathEx::setInterlockingJointPairIndices (const std::vector<std::pair<size_t, size_t> >& pairs) {
153  return true;
154 };
155 
156 void JointPathEx::getInterlockingJointPairIndices (std::vector<std::pair<size_t, size_t> >& pairs) {
158 };
159 
161  const int n = numJoints();
162 
163  hrp::dmatrix w = hrp::dmatrix::Identity(n,n);
164  //
165  // wmat/weight: weighting joint angle weight
166  //
167  // w_i = 1 + | dH/dt | if d|dH/dt| >= 0
168  // = 1 if d|dH/dt| < 0
169  // dH/dt = (t_max - t_min)^2 (2t - t_max - t_min)
170  // / 4 (t_max - t)^2 (t - t_min)^2
171  //
172  // T. F. Chang and R.-V. Dubey: "A weighted least-norm solution based
173  // scheme for avoiding joint limits for redundant manipulators", in IEEE
174  // Trans. On Robotics and Automation, 11((2):286-292, April 1995.
175  //
176  for ( int j = 0; j < n ; j++ ) {
177  double jang = joints[j]->q;
178  double jmax = joints[j]->ulimit;
179  double jmin = joints[j]->llimit;
180  double e = deg2rad(1);
181  if ( eps_eq(jang, jmax,e) && eps_eq(jang, jmin,e) ) {
182  } else if ( eps_eq(jang, jmax,e) ) {
183  jang = jmax - e;
184  } else if ( eps_eq(jang, jmin,e) ) {
185  jang = jmin + e;
186  }
187 
188  double r;
189  if ( eps_eq(jang, jmax,e) && eps_eq(jang, jmin,e) ) {
190  r = DBL_MAX;
191  } else {
192  r = fabs( (pow((jmax - jmin),2) * (( 2 * jang) - jmax - jmin)) /
193  (4 * pow((jmax - jang),2) * pow((jang - jmin),2)) );
194  if (std::isnan(r)) r = 0;
195  }
196 
197  // If use_inside_joint_weight_retrieval = true (true by default), use T. F. Chang and R.-V. Dubeby weight retrieval inward.
198  // Otherwise, joint weight is always calculated from limit value to resolve https://github.com/fkanehiro/hrpsys-base/issues/516.
199  if (( r - avoid_weight_gain[j] ) >= 0 ) {
200  w(j, j) = optional_weight_vector[j] * ( 1.0 / ( 1.0 + r) );
201  } else {
203  w(j, j) = optional_weight_vector[j] * 1.0;
204  else
205  w(j, j) = optional_weight_vector[j] * ( 1.0 / ( 1.0 + r) );
206  }
207  avoid_weight_gain[j] = r;
208  }
209  if ( DEBUG ) {
210  std::cerr << " cost :";
211  for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << avoid_weight_gain[j]; }
212  std::cerr << std::endl;
213  std::cerr << " optw :";
214  for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << optional_weight_vector[j]; }
215  std::cerr << std::endl;
216  std::cerr << " w :";
217  for(int j = 0; j < n; j++ ) { std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << w(j, j); }
218  std::cerr << std::endl;
219  }
220 
221  double manipulability = sqrt((J*J.transpose()).determinant());
222  double k = 0;
223  if ( manipulability < manipulability_limit ) {
224  k = manipulability_gain * pow((1 - ( manipulability / manipulability_limit )), 2);
225  }
226  if ( DEBUG ) {
227  std::cerr << " manipulability = " << manipulability << " < " << manipulability_limit << ", k = " << k << " -> " << sr_gain * k << std::endl;
228  }
229 
230  calcSRInverse(J, Jinv, sr_gain * k, w);
231 
232  Jnull = ( hrp::dmatrix::Identity(n, n) - Jinv * J);
233 
234  return true;
235 }
236 
238  const double LAMBDA, const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q) {
239  const int n = numJoints();
240 
241  if ( DEBUG ) {
242  std::cerr << "angle :";
243  for(int j=0; j < n; ++j){
244  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(joints[j]->q);
245  }
246  std::cerr << endl;
247  }
248 
249  size_t ee_workspace_dim = 6; // End-effector workspace dimensions including pos(3) and rot(3)
250  size_t ij_workspace_dim = interlocking_joint_pair_indices.size(); // Dimensions for interlocking joints constraint. 0 by default.
251  size_t workspace_dim = ee_workspace_dim + ij_workspace_dim;
252 
253  // Total jacobian, workspace velocty, and so on
254  hrp::dmatrix J(workspace_dim, n);
255  dvector v(workspace_dim);
256  hrp::dmatrix Jinv(n, workspace_dim);
257  hrp::dmatrix Jnull(n, n);
258  hrp::dvector dq(n);
259 
260  if (ij_workspace_dim > 0) {
261  v << dp, omega, dvector::Zero(ij_workspace_dim);
262  hrp::dmatrix ee_J = dmatrix::Zero(ee_workspace_dim, n);
263  calcJacobian(ee_J);
264  hrp::dmatrix ij_J = dmatrix::Zero(ij_workspace_dim, n);
265  for (size_t i = 0; i < ij_workspace_dim; i++) {
266  std::pair<size_t, size_t>& pair = interlocking_joint_pair_indices[i];
267  ij_J(i, pair.first) = 1;
268  ij_J(i, pair.second) = -1;
269  }
270  J << ee_J, ij_J;
271  } else {
272  v << dp, omega;
273  calcJacobian(J);
274  }
275  calcJacobianInverseNullspace(J, Jinv, Jnull);
276  dq = Jinv * v; // dq = pseudoInverse(J) * v
277 
278  if ( DEBUG ) {
279  std::cerr << " v :";
280  for(int j=0; j < v.size(); ++j){
281  std::cerr << " " << v(j);
282  }
283  std::cerr << std::endl;
284  std::cerr << " J :" << std::endl << J;
285  std::cerr << " Jinv :" << std::endl << Jinv;
286  }
287  // If avoid_gain is set, add joint limit avoidance by null space vector
288  if ( avoid_gain > 0.0 ) {
289  // dq = J#t a dx + ( I - J# J ) Jt b dx
290  // avoid-nspace-joint-limit: avoiding joint angle limit
291  //
292  // dH/dq = (((t_max + t_min)/2 - t) / ((t_max - t_min)/2)) ^2
293  hrp::dvector u(n);
294  for ( int j = 0; j < n ; j++ ) {
295  double jang = joint(j)->q;
296  double jmax = joint(j)->ulimit;
297  double jmin = joint(j)->llimit;
298  double r = ((( (jmax + jmin) / 2.0) - jang) / ((jmax - jmin) / 2.0));
299  if ( r > 0 ) { r = r*r; } else { r = - r*r; }
300  u[j] = optional_weight_vector[j] * avoid_gain * r;
301  }
302  if ( DEBUG ) {
303  std::cerr << " u(jl):";
304  for(int j=0; j < n; ++j){
305  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(u(j));
306  }
307  std::cerr << std::endl;
308  std::cerr << " JN*u :";
309  hrp::dvector Jnullu = Jnull * u;
310  for(int j=0; j < n; ++j){
311  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(Jnullu(j));
312  }
313  std::cerr << std::endl;
314  }
315  dq = dq + Jnull * u;
316  }
317  // If reference_gain and reference_q are set, add following to reference_q by null space vector
318  if ( reference_gain > 0.0 && reference_q != NULL ) {
319  //
320  // qref - qcurr
321  hrp::dvector u(n);
322  for ( unsigned int j = 0; j < numJoints(); j++ ) {
323  u[j] = optional_weight_vector[j] * reference_gain * ( (*reference_q)[joint(j)->jointId] - joint(j)->q );
324  }
325  if ( DEBUG ) {
326  std::cerr << "u(ref):";
327  for(int j=0; j < n; ++j){
328  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(u(j));
329  }
330  std::cerr << std::endl;
331  std::cerr << " JN*u:";
332  hrp::dvector nullu = Jnull * u;
333  for(int j=0; j < n; ++j){
334  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(nullu(j));
335  }
336  std::cerr << std::endl;
337  }
338  dq = dq + Jnull * u;
339  }
340  if ( DEBUG ) {
341  std::cerr << " dq :";
342  for(int j=0; j < n; ++j){
343  std::cerr << std::setw(8) << std::setiosflags(std::ios::fixed) << std::setprecision(4) << rad2deg(dq(j));
344  }
345  std::cerr << std::endl;
346  }
347 
348  // dq limitation using lvlimit/uvlimit
349  double min_speed_ratio = 1.0;
350  for(int j=0; j < n; ++j){
351  double speed_ratio = 1.0;
352  if (dq(j) < joints[j]->lvlimit * dt) {
353  speed_ratio = fabs(joints[j]->lvlimit * dt / dq(j));
354  } else if (dq(j) > joints[j]->uvlimit * dt) {
355  speed_ratio = fabs(joints[j]->uvlimit * dt / dq(j));
356  }
357  min_speed_ratio = std::max(std::min(min_speed_ratio, speed_ratio), 0.0);
358  }
359  if ( min_speed_ratio < 1.0 ) {
360  if ( DEBUG ) {
361  std::cerr << "spdlmt: ";
362  for(int j=0; j < n; ++j) { std::cerr << dq(j) << " "; } std::cerr << std::endl;
363  }
364  for(int j=0; j < n; ++j) {
365  dq(j) = dq(j) * min_speed_ratio; // make
366  }
367  if ( DEBUG ) {
368  std::cerr << "spdlmt: ";
369  for(int j=0; j < n; ++j) { std::cerr << dq(j) << " "; } std::cerr << std::endl;
370  }
371  }
372 
373  // check nan / inf
374  bool solve_linear_equation = true;
375  for(int j=0; j < n; ++j){
376  if ( std::isnan(dq(j)) || std::isinf(dq(j)) ) {
377  solve_linear_equation = false;
378  break;
379  }
380  }
381  if ( ! solve_linear_equation ) {
382  std::cerr << "[" << debug_print_prefix << "] ERROR nan/inf is found" << std::endl;
383  return false;
384  }
385 
386  // joint angles update
387  for(int j=0; j < n; ++j){
388  joints[j]->q += LAMBDA * dq(j);
389  }
390 
391  // If interlocking joints are defined, set interlocking joints by mid point
392  for (size_t i = 0; i < interlocking_joint_pair_indices.size(); i++) {
393  std::pair<size_t, size_t>& pair = interlocking_joint_pair_indices[i];
394  double midp = (joints[pair.first]->q + joints[pair.second]->q)/2.0;
395  joints[pair.first]->q = midp;
396  joints[pair.second]->q = midp;
397  }
398 
399  // upper/lower limit check
400  for(int j=0; j < n; ++j){
401  bool is_limit_over = false;
402  if ( joints[j]->q > joints[j]->ulimit) {
403  is_limit_over = true;
405  std::cerr << "[" << debug_print_prefix << "] Upper joint limit over " << joints[j]->name
406  << " (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;
407  }
408  joints[j]->q = joints[j]->ulimit;
409  }
410  if ( joints[j]->q < joints[j]->llimit) {
411  is_limit_over = true;
413  std::cerr << "[" << debug_print_prefix << "] Lower joint limit over " << joints[j]->name
414  << " (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;
415  }
416  joints[j]->q = joints[j]->llimit;
417  }
418  joints[j]->q = std::max(joints[j]->q, joints[j]->llimit);
419  if (is_limit_over) {
421  } else {
422  joint_limit_debug_print_counts[j] = 0; // resetting
423  }
424  }
425 
427 
428  return true;
429 }
430 
431 // TODO : matrix_logEx should be omegaFromRotEx after checking on real robot testing.
433  hrp::Vector3 mlog;
434  double q0, th;
435  hrp::Vector3 q;
436  double norm;
437 
438  Eigen::Quaternion<double> eiq(m);
439  q0 = eiq.w();
440  q = eiq.vec();
441  norm = q.norm();
442  if (norm > 0) {
443  if ((q0 > 1.0e-10) || (q0 < -1.0e-10)) {
444  th = 2 * std::atan(norm / q0);
445  } else if (q0 > 0) {
446  th = M_PI / 2;
447  } else {
448  th = -M_PI / 2;
449  }
450  mlog = (th / norm) * q ;
451  } else {
452  mlog = hrp::Vector3::Zero();
453  }
454  return mlog;
455 }
456 
457 bool JointPathEx::calcInverseKinematics2Loop(const Vector3& end_effector_p, const Matrix33& end_effector_R,
458  const double LAMBDA, const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q,
459  const double vel_gain,
460  const hrp::Vector3& localPos, const hrp::Matrix33& localR)
461 {
462  hrp::Matrix33 target_link_R(end_effector_R * localR.transpose());
463  hrp::Vector3 target_link_p(end_effector_p - target_link_R * localPos);
464  hrp::Vector3 vel_p(target_link_p - endLink()->p);
465  // TODO : matrix_logEx should be omegaFromRotEx after checking on real robot testing.
466  //hrp::Vector3 vel_r(endLink()->R * omegaFromRotEx(endLink()->R.transpose() * target_link_R));
467  hrp::Vector3 vel_r(endLink()->R * matrix_logEx(endLink()->R.transpose() * target_link_R));
468  vel_p *= vel_gain;
469  vel_r *= vel_gain;
470  return calcInverseKinematics2Loop(vel_p, vel_r, LAMBDA, avoid_gain, reference_gain, reference_q);
471 }
472 
473 bool JointPathEx::calcInverseKinematics2(const Vector3& end_p, const Matrix33& end_R,
474  const double avoid_gain, const double reference_gain, const hrp::dvector* reference_q)
475 {
476  static const int MAX_IK_ITERATION = maxIKIteration;
477  static const double LAMBDA = 0.9;
478 
480 
481  if(joints.empty()){
482  if(linkPath.empty()){
483  return false;
484  }
485  if(baseLink() == endLink()){
486  baseLink()->p = end_p;
487  baseLink()->R = end_R;
488  return true;
489  } else {
490  // \todo implement here
491  return false;
492  }
493  }
494 
495  const int n = numJoints();
496  dvector qorg(n);
497 
498  Link* target = linkPath.endLink();
499 
500  for(int i=0; i < n; ++i){
501  qorg[i] = joints[i]->q;
502  avoid_weight_gain[i] = 100000000000000000000.0;
503  }
504 
505 
506  double errsqr = DBL_MAX;//maxIKErrorSqr * 100.0;
507  double errsqr0 = errsqr;
508  bool converged = false;
509 
510  int iter = 0;
511  for(iter = 0; iter < MAX_IK_ITERATION; iter++){
512 
513  if ( DEBUG ) {
514  std::cerr << " iter : " << iter << " / " << MAX_IK_ITERATION << ", n = " << n << std::endl;
515  }
516 
517  Vector3 dp(end_p - target->p);
518  Vector3 omega(target->R * omegaFromRotEx(target->R.transpose() * end_R));
519  if ( dp.norm() > 0.1 ) dp = dp*0.1/dp.norm();
520  if ( omega.norm() > 0.5 ) omega = omega*0.5/omega.norm();
521 
522 
523  if ( DEBUG ) {
524  std::cerr << " dp : " << dp[0] << " " << dp[1] << " " << dp[2] << std::endl;
525  std::cerr << "omega : " << omega[0] << " " << omega[1] << " " << omega[2] << std::endl;
526  //std::cerr << " J :" << std::endl << J;
527  //std::cerr << " det : " << det(J) << std::endl;
528  std::cerr << " err : dp = " << dp.dot(dp) << ", omega = " << omega.dot(omega) << std::endl;
529  }
530 
531  if(isBestEffortIKMode){
532  errsqr0 = errsqr;
533  errsqr = dp.dot(dp) + omega.dot(omega);
534  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;
535  if(fabs(errsqr - errsqr0) < maxIKErrorSqr){
536  converged = true;
537  break;
538  }
539  } else {
540  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;
541  if( (dp.dot(dp) < maxIKPosErrorSqr) && (omega.dot(omega) < maxIKRotErrorSqr) ) {
542  converged = true;
543  break;
544  }
545  }
546 
547  if ( !calcInverseKinematics2Loop(dp, omega, LAMBDA, avoid_gain, reference_gain, reference_q) )
548  return false;
549  }
550 
551  if(!converged){
552  std::cerr << "IK Fail, iter = " << iter << std::endl;
553  Vector3 dp(end_p - target->p);
554  Vector3 omega(target->R * omegaFromRotEx(target->R.transpose() * end_R));
555  const double errsqr = dp.dot(dp) + omega.dot(omega);
556  if(isBestEffortIKMode){
557  std::cerr << " err : fabs(" << errsqr << " - " << errsqr0 << ") = " << fabs(errsqr-errsqr0) << " < " << maxIKErrorSqr << " BestEffortIKMode" << std::endl;
558  } else {
559  std::cerr << " err : " << dp.dot(dp) << " ( " << dp[0] << " " << dp[1] << " " << dp[2] << ") < " << maxIKPosErrorSqr << std::endl;
560  std::cerr << " : " << omega.dot(omega) << " ( " << omega[0] << " " << omega[1] << " " << omega[2] << ") < " << maxIKRotErrorSqr << std::endl;
561  }
562  for(int i=0; i < n; ++i){
563  joints[i]->q = qorg[i];
564  }
566  }
567 
568  return converged;
569 }
570 
571 void hrp::readVirtualForceSensorParamFromProperties (std::map<std::string, hrp::VirtualForceSensorParam>& vfs,
573  const std::string& prop_string,
574  const std::string& instance_name)
575 {
576  coil::vstring virtual_force_sensor = coil::split(prop_string, ",");
577  unsigned int nvforce = virtual_force_sensor.size()/10;
578  for (unsigned int i=0; i<nvforce; i++){
579  std::string name = virtual_force_sensor[i*10+0];
580  hrp::dvector tr(7);
581  for (int j = 0; j < 7; j++ ) {
582  coil::stringTo(tr[j], virtual_force_sensor[i*10+3+j].c_str());
583  }
584  vfs.insert(std::pair<std::string, VirtualForceSensorParam>(name, VirtualForceSensorParam()));
585  VirtualForceSensorParam& p = vfs[name];
586  p.localPos = hrp::Vector3(tr[0], tr[1], tr[2]);
587  p.localR = Eigen::AngleAxis<double>(tr[6], hrp::Vector3(tr[3],tr[4],tr[5])).toRotationMatrix(); // rotation in VRML is represented by axis + angle
588  p.link = m_robot->link(virtual_force_sensor[i*10+2]);
589  p.id = i;
590  std::cerr << "[" << instance_name << "] virtual force sensor" << std::endl;
591  std::cerr << "[" << instance_name << "] name = " << name << ", parent = " << p.link->name << ", id = " << p.id << std::endl;
592  std::cerr << "[" << instance_name << "] localP = " << p.localPos.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", ", ", "", "", "[", "]")) << "[m]" << std::endl;
593  std::cerr << "[" << instance_name << "] localR = " << p.localR.format(Eigen::IOFormat(Eigen::StreamPrecision, 0, ", ", "\n", " [", "]")) << std::endl;
594  }
595 };
596 
597 void hrp::readInterlockingJointsParamFromProperties (std::vector<std::pair<Link*, Link*> >& pairs,
599  const std::string& prop_string,
600  const std::string& instance_name)
601 {
602  coil::vstring interlocking_joints_str = coil::split(prop_string, ",");
603  size_t ij_prop_num = 2;
604  if (interlocking_joints_str.size() > 0) {
605  size_t num = interlocking_joints_str.size()/ij_prop_num;
606  for (size_t i = 0; i < num; i++) {
607  //std::cerr << "[" << instance_name << "] Interlocking Joints [" << interlocking_joints_str[i*ij_prop_num] << "], [" << interlocking_joints_str[i*ij_prop_num+1] << "]" << std::endl;
608  hrp::Link* link1 = m_robot->link(interlocking_joints_str[i*ij_prop_num]);
609  hrp::Link* link2 = m_robot->link(interlocking_joints_str[i*ij_prop_num+1]);
610  if (link1 == NULL || link2 == NULL) {
611  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;
612  continue;
613  }
614  std::pair<hrp::Link*, hrp::Link*> pair(link1, link2);
615  pairs.push_back(pair);
616  };
617  }
618 };
619 
621  for(int i=0;i<_m_robot->numJoints();i++)_idsb.q(i) = _m_robot->joint(i)->q;
622  _idsb.dq = (_idsb.q - _idsb.q_old) / _idsb.DT;
623  _idsb.ddq = (_idsb.q - 2 * _idsb.q_old + _idsb.q_oldold) / (_idsb.DT * _idsb.DT);
624  const hrp::Vector3 g(0, 0, 9.80665);
625  _idsb.base_p = _m_robot->rootLink()->p;
626  _idsb.base_v = (_idsb.base_p - _idsb.base_p_old) / _idsb.DT;
627  _idsb.base_dv = g + (_idsb.base_p - 2 * _idsb.base_p_old + _idsb.base_p_oldold) / (_idsb.DT * _idsb.DT);
628  _idsb.base_R = _m_robot->rootLink()->R;
629  _idsb.base_dR = (_idsb.base_R - _idsb.base_R_old) / _idsb.DT;
630  _idsb.base_w_hat = _idsb.base_dR * _idsb.base_R.transpose();
631  _idsb.base_w = hrp::Vector3(_idsb.base_w_hat(2,1), - _idsb.base_w_hat(0,2), _idsb.base_w_hat(1,0));
632  _idsb.base_dw = (_idsb.base_w - _idsb.base_w_old) / _idsb.DT;
633 };
634 
636  for(int i=0;i<_m_robot->numJoints();i++){
637  _m_robot->joint(i)->dq = _idsb.dq(i);
638  _m_robot->joint(i)->ddq = _idsb.ddq(i);
639  }
640  _m_robot->rootLink()->vo = _idsb.base_v - _idsb.base_w.cross(_idsb.base_p);
641  _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
642  _m_robot->rootLink()->w = _idsb.base_w;
643  _m_robot->rootLink()->dw = _idsb.base_dw;
644  _m_robot->calcForwardKinematics(true,true);// calc every link's acc and vel
645  _m_robot->calcInverseDynamics(_m_robot->rootLink(), _f_ans, _t_ans);// this returns f,t at the coordinate origin (not at base link pos)
646 };
647 
649  hrp::Vector3 f_tmp, t_tmp;
650  calcRootLinkWrenchFromInverseDynamics(_m_robot, _idsb, f_tmp, t_tmp);
651  _zmp_ans(0) = -t_tmp(1)/f_tmp(2);
652  _zmp_ans(1) = t_tmp(0)/f_tmp(2);
653 };
654 
656  _idsb.q_oldold = _idsb.q_old;
657  _idsb.q_old = _idsb.q;
658  _idsb.base_p_oldold = _idsb.base_p_old;
659  _idsb.base_p_old = _idsb.base_p;
660  _idsb.base_R_old = _idsb.base_R;
661  _idsb.base_w_old = _idsb.base_w;
662 };
bool calcJacobianInverseNullspace(dmatrix &J, dmatrix &Jinv, dmatrix &Jnull)
double maxIKRotErrorSqr
Definition: JointPathEx.h:48
#define max(a, b)
std::vector< Link * > joints
Definition: JointPathEx.h:52
Eigen::MatrixXd dmatrix
void readInterlockingJointsParamFromProperties(std::vector< std::pair< Link *, Link * > > &pairs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
Link * baseLink() const
bool stringTo(To &val, const char *str)
#define DEBUG
Definition: JointPathEx.cpp:37
double maxIKErrorSqr
png_infop png_charpp name
vstring split(const std::string &input, const std::string &delimiter, bool ignore_empty)
#define deg2rad(x)
Definition: JointPathEx.cpp:8
std::ostream & operator<<(std::ostream &out, hrp::dmatrix &a)
Definition: JointPathEx.cpp:12
hrp::Matrix33 base_dR
Definition: JointPathEx.h:96
std::vector< std::pair< size_t, size_t > > interlocking_joint_pair_indices
Definition: JointPathEx.h:58
w
OpenHRP::matrix33 Matrix33
png_uint_32 i
Eigen::VectorXd dvector
dmatrix inverse(const dmatrix &M)
LinkPath linkPath
hrp::Matrix33 base_R
Definition: JointPathEx.h:96
std::vector< double > avoid_weight_gain
Definition: JointPathEx.h:53
hrp::Vector3 base_p
Definition: JointPathEx.h:95
hrp::dvector q_old
Definition: JointPathEx.h:94
void calcRootLinkWrenchFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb, hrp::Vector3 &_f_ans, hrp::Vector3 &_t_ans)
Eigen::Vector3d Vector3
hrp::Vector3 base_v
Definition: JointPathEx.h:95
bool setInterlockingJointPairIndices(const std::vector< std::pair< Link *, Link * > > &pairs, const std::string &print_str="")
#define eps_eq(a, b, c)
Definition: JointPathEx.cpp:10
Eigen::Matrix3d Matrix33
#define min(a, b)
std::vector< std::string > vstring
void setMaxIKIteration(int iter)
OpenHRP::vector3 Vector3
hrp::Vector3 base_w
Definition: JointPathEx.h:97
void calcJacobian(dmatrix &out_J, const Vector3 &local_p=Vector3::Zero()) const
#define rad2deg(rad)
Definition: JointPathEx.cpp:9
void calcAccelerationsForInverseDynamics(const hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb)
void calcForwardKinematics(bool calcVelocity=false, bool calcAcceleration=false) const
std::vector< size_t > joint_limit_debug_print_counts
Definition: JointPathEx.h:62
hrp::Vector3 matrix_logEx(const hrp::Matrix33 &m)
hrp::Vector3 base_p_old
Definition: JointPathEx.h:95
def j(str, encoding="cp932")
int calcSRInverse(const dmatrix &_a, dmatrix &_a_sr, double _sr_ratio, dmatrix _w)
Definition: JointPathEx.cpp:42
bool calcInverseKinematics2(const Vector3 &end_p, const Matrix33 &end_R, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
void getInterlockingJointPairIndices(std::vector< std::pair< size_t, size_t > > &pairs)
Link * joint(int index) const
hrp::Matrix33 base_w_hat
Definition: JointPathEx.h:96
n
hrp::Vector3 base_p_oldold
Definition: JointPathEx.h:95
unsigned int numJoints() const
hrp::Vector3 base_dw
Definition: JointPathEx.h:97
Link * endLink() const
bool use_inside_joint_weight_retrieval
Definition: JointPathEx.h:64
bool empty() const
double manipulability_gain
Definition: JointPathEx.h:59
def norm(a)
void readVirtualForceSensorParamFromProperties(std::map< std::string, hrp::VirtualForceSensorParam > &vfs, hrp::BodyPtr m_robot, const std::string &prop_string, const std::string &instance_name)
void setMaxIKError(double epos, double erot)
#define M_PI
bool isBestEffortIKMode
std::string debug_print_prefix
Definition: JointPathEx.h:60
hrp::Matrix33 base_R_old
Definition: JointPathEx.h:96
Vector3 omegaFromRotEx(const Matrix33 &r)
Definition: JointPathEx.cpp:68
bool calcInverseKinematics2Loop(const Vector3 &dp, const Vector3 &omega, const double LAMBDA, const double avoid_gain=0.0, const double reference_gain=0.0, const dvector *reference_q=NULL)
hrp::BodyPtr m_robot
hrp::Vector3 base_dv
Definition: JointPathEx.h:95
int num
std::vector< double > optional_weight_vector
Definition: JointPathEx.h:53
hrp::Vector3 base_w_old
Definition: JointPathEx.h:97
double maxIKPosErrorSqr
Definition: JointPathEx.h:48
Link * endLink() const
void updateInvDynStateBuffer(InvDynStateBuffer &_idsb)
size_t debug_print_freq_count
Definition: JointPathEx.h:63
double manipulability_limit
Definition: JointPathEx.h:59
hrp::dvector q_oldold
Definition: JointPathEx.h:94
void calcWorldZMPFromInverseDynamics(hrp::BodyPtr _m_robot, InvDynStateBuffer &_idsb, hrp::Vector3 &_zmp_ans)


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Thu May 6 2021 02:41:50