sot-talos-balance  2.0.5
Collection of dynamic-graph entities aimed at implementing balance control on talos.
distribute-wrench.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Gepetto team, LAAS-CNRS
3  *
4  * This file is part of sot-talos-balance.
5  * sot-talos-balance is free software: you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public License
7  * as published by the Free Software Foundation, either version 3 of
8  * the License, or (at your option) any later version.
9  * sot-talos-balance is distributed in the hope that it will be
10  * useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11  * of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details. You should
13  * have received a copy of the GNU Lesser General Public License along
14  * with sot-talos-balance. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
18 
19 #include <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/factory.h>
21 
22 #include <iostream>
23 #include <pinocchio/algorithm/frames.hpp>
24 #include <pinocchio/algorithm/kinematics.hpp>
25 #include <pinocchio/parsers/urdf.hpp>
26 #include <sot/core/debug.hh>
27 #include <sot/core/stop-watch.hh>
28 
29 namespace dynamicgraph {
30 namespace sot {
31 namespace talos_balance {
32 namespace dg = ::dynamicgraph;
33 using namespace dg;
34 using namespace dg::command;
35 using namespace eiquadprog::solvers;
36 
37 // Size to be aligned "-------------------------------------------------------"
38 #define PROFILE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS \
39  "DistributeWrench: kinematics computations "
40 #define PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS \
41  "DistributeWrench: QP problem computations "
42 
43 #define WEIGHT_SIGNALS m_wSumSIN << m_wNormSIN << m_wRatioSIN << m_wAnkleSIN
44 
45 #define INPUT_SIGNALS \
46  m_wrenchDesSIN << m_qSIN << m_rhoSIN << m_phaseSIN \
47  << m_frictionCoefficientSIN << WEIGHT_SIGNALS
48 
49 #define INNER_SIGNALS m_kinematics_computations << m_qp_computations
50 
51 #define OUTPUT_SIGNALS \
52  m_wrenchLeftSOUT << m_ankleWrenchLeftSOUT << m_surfaceWrenchLeftSOUT \
53  << m_copLeftSOUT << m_wrenchRightSOUT \
54  << m_ankleWrenchRightSOUT << m_surfaceWrenchRightSOUT \
55  << m_copRightSOUT << m_wrenchRefSOUT << m_zmpRefSOUT \
56  << m_emergencyStopSOUT
57 
60 typedef DistributeWrench EntityClassName;
61 
62 /* --- DG FACTORY ---------------------------------------------------- */
63 DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(DistributeWrench, "DistributeWrench");
64 
65 /* ------------------------------------------------------------------- */
66 /* --- CONSTRUCTION -------------------------------------------------- */
67 /* ------------------------------------------------------------------- */
69  : Entity(name),
70  CONSTRUCT_SIGNAL_IN(wrenchDes, dynamicgraph::Vector),
71  CONSTRUCT_SIGNAL_IN(q, dynamicgraph::Vector),
72  CONSTRUCT_SIGNAL_IN(rho, double),
73  CONSTRUCT_SIGNAL_IN(phase, int),
74  CONSTRUCT_SIGNAL_IN(frictionCoefficient, double),
75  CONSTRUCT_SIGNAL_IN(wSum, double),
76  CONSTRUCT_SIGNAL_IN(wNorm, double),
77  CONSTRUCT_SIGNAL_IN(wRatio, double),
78  CONSTRUCT_SIGNAL_IN(wAnkle, dynamicgraph::Vector),
79  CONSTRUCT_SIGNAL_INNER(kinematics_computations, int, m_qSIN),
80  CONSTRUCT_SIGNAL_INNER(qp_computations, int,
81  m_wrenchDesSIN << m_rhoSIN << m_phaseSIN
83  << m_kinematics_computationsSINNER),
84  CONSTRUCT_SIGNAL_OUT(wrenchLeft, dynamicgraph::Vector,
85  m_qp_computationsSINNER),
86  CONSTRUCT_SIGNAL_OUT(ankleWrenchLeft, dynamicgraph::Vector,
87  m_wrenchLeftSOUT),
88  CONSTRUCT_SIGNAL_OUT(surfaceWrenchLeft, dynamicgraph::Vector,
89  m_wrenchLeftSOUT),
90  CONSTRUCT_SIGNAL_OUT(copLeft, dynamicgraph::Vector, m_wrenchLeftSOUT),
91  CONSTRUCT_SIGNAL_OUT(wrenchRight, dynamicgraph::Vector,
92  m_qp_computationsSINNER),
93  CONSTRUCT_SIGNAL_OUT(ankleWrenchRight, dynamicgraph::Vector,
94  m_wrenchRightSOUT),
95  CONSTRUCT_SIGNAL_OUT(surfaceWrenchRight, dynamicgraph::Vector,
96  m_wrenchRightSOUT),
97  CONSTRUCT_SIGNAL_OUT(copRight, dynamicgraph::Vector, m_wrenchRightSOUT),
98  CONSTRUCT_SIGNAL_OUT(wrenchRef, dynamicgraph::Vector,
99  m_wrenchLeftSOUT << m_wrenchRightSOUT),
100  CONSTRUCT_SIGNAL_OUT(zmpRef, dynamicgraph::Vector, m_wrenchRefSOUT),
101  CONSTRUCT_SIGNAL_OUT(emergencyStop, bool, m_zmpRefSOUT),
102  m_initSucceeded(false),
103  m_model(),
104  m_data(pinocchio::Model()),
105  m_Q1(6, 6),
106  m_C1(6),
107  m_Aeq1(0, 6),
108  m_Beq1(0),
109  m_Aineq1(16, 6),
110  m_Bineq1(16),
111  m_result1(6),
112  m_Q2(12, 12),
113  m_C2(12),
114  m_Aeq2(0, 12),
115  m_Beq2(0),
116  m_Aineq2(34, 12),
117  m_Bineq2(34),
118  m_result2(12),
119  m_wAnkle(6) {
120  Entity::signalRegistration(INPUT_SIGNALS << OUTPUT_SIGNALS);
121 
122  m_qp1.reset(6, 0, 16);
123  m_qp2.reset(12, 0, 34);
124 
125  /* Commands. */
126  addCommand("init", makeCommandVoid1(*this, &DistributeWrench::init,
127  docCommandVoid1("Initialize the entity.",
128  "Robot name")));
129 
130  addCommand(
131  "set_right_foot_sizes",
132  makeCommandVoid1(
134  docCommandVoid1(
135  "Set the size of the right foot (pos x, neg x, pos y, neg y)",
136  "4d vector")));
137  addCommand(
138  "set_left_foot_sizes",
139  makeCommandVoid1(
141  docCommandVoid1(
142  "Set the size of the left foot (pos x, neg x, pos y, neg y)",
143  "4d vector")));
144 
145  addCommand(
146  "getMinPressure",
147  makeDirectGetter(*this, &m_eps,
148  docDirectGetter("Get minimum pressure", "double")));
149  addCommand(
150  "setMinPressure",
151  makeDirectSetter(*this, &m_eps,
152  docDirectSetter("Set minimum pressure", "double")));
153 
154  m_eps = 15.; // TODO: signal/conf
155 }
156 
157 void DistributeWrench::init(const std::string& robotName) {
158  if (!m_wrenchDesSIN.isPlugged())
159  return SEND_MSG("Init failed: signal wrenchDes is not plugged",
160  MSG_TYPE_ERROR);
161  if (!m_qSIN.isPlugged())
162  return SEND_MSG("Init failed: signal q is not plugged", MSG_TYPE_ERROR);
163 
164  if (m_left_foot_sizes.size() == 0)
165  return SEND_ERROR_STREAM_MSG(
166  "Init failed: left foot size is not initialized");
167  if (m_right_foot_sizes.size() == 0)
168  return SEND_ERROR_STREAM_MSG(
169  "Init failed: right foot size is not initialized");
170 
171  try {
172  /* Retrieve m_robot_util informations */
173  std::string localName(robotName);
174  if (isNameInRobotUtil(localName)) {
175  m_robot_util = getRobotUtil(localName);
176  // std::cerr << "m_robot_util:" << m_robot_util << std::endl;
177  } else {
178  SEND_MSG("You should have a robotUtil pointer initialized before",
179  MSG_TYPE_ERROR);
180  return;
181  }
182 
183  pinocchio::urdf::buildModel(m_robot_util->m_urdf_filename,
184  pinocchio::JointModelFreeFlyer(), m_model);
185  m_data = pinocchio::Data(m_model);
186  } catch (const std::exception& e) {
187  std::cout << e.what();
188  SEND_MSG("Init failed: Could load URDF :" + m_robot_util->m_urdf_filename,
189  MSG_TYPE_ERROR);
190  return;
191  }
192 
193  assert(m_model.existFrame(m_robot_util->m_foot_util.m_Left_Foot_Frame_Name));
194  assert(m_model.existFrame(m_robot_util->m_foot_util.m_Right_Foot_Frame_Name));
196  m_model.getFrameId(m_robot_util->m_foot_util.m_Left_Foot_Frame_Name);
198  m_model.getFrameId(m_robot_util->m_foot_util.m_Right_Foot_Frame_Name);
199 
200  // m_ankle_M_ftSens = pinocchio::SE3(Eigen::Matrix3d::Identity(),
201  // m_robot_util->m_foot_util.m_Right_Foot_Force_Sensor_XYZ.head<3>());
203  pinocchio::SE3(Eigen::Matrix3d::Identity(),
204  m_robot_util->m_foot_util.m_Right_Foot_Sole_XYZ.head<3>());
205 
206  m_initSucceeded = true;
207 }
208 
210  if (s.size() != 4)
211  return SEND_MSG(
212  "Foot size vector should have size 4, not " + toString(s.size()),
213  MSG_TYPE_ERROR);
214  m_right_foot_sizes = s;
215 }
216 
218  if (s.size() != 4)
219  return SEND_MSG(
220  "Foot size vector should have size 4, not " + toString(s.size()),
221  MSG_TYPE_ERROR);
222  m_left_foot_sizes = s;
223 }
224 
225 // WARNING: we are assuming wrench = right = symmetrical
227  const double X = m_right_foot_sizes[0];
228  const double Y = m_right_foot_sizes[2];
230  // fx, fy, fz, mx, my, mz,
231  -1,
232  0, -mu, 0, 0, 0, +1, 0, -mu, 0, 0, 0, 0, -1, -mu, 0, 0, 0, 0, +1, -mu, 0,
233  0, 0, 0, 0, -Y, -1, 0, 0, 0, 0, -Y, +1, 0, 0, 0, 0, -X, 0, -1, 0, 0, 0,
234  -X, 0, +1, 0, -Y, -X, -(X + Y) * mu, +mu, +mu, -1, -Y, +X, -(X + Y) * mu,
235  +mu, -mu, -1, +Y, -X, -(X + Y) * mu, -mu, +mu, -1, +Y, +X, -(X + Y) * mu,
236  -mu, -mu, -1, +Y, +X, -(X + Y) * mu, +mu, +mu, +1, +Y, -X, -(X + Y) * mu,
237  +mu, -mu, +1, -Y, +X, -(X + Y) * mu, -mu, +mu, +1, -Y, -X, -(X + Y) * mu,
238  -mu, -mu, +1;
239 }
240 
241 Eigen::Vector3d DistributeWrench::computeCoP(const dg::Vector& wrenchGlobal,
242  const pinocchio::SE3& pose) const {
244  pose.actInv(pinocchio::Force(wrenchGlobal)).toVector();
245 
246  const double h = pose.translation()[2];
247 
248  const double fx = wrench[0];
249  const double fy = wrench[1];
250  const double fz = wrench[2];
251  const double tx = wrench[3];
252  const double ty = wrench[4];
253 
254  double m_eps = 0.1; // temporary
255 
256  double px, py;
257 
258  if (fz >= m_eps / 2) {
259  px = (-ty - fx * h) / fz;
260  py = (tx - fy * h) / fz;
261  } else {
262  px = 0.0;
263  py = 0.0;
264  }
265  const double pz = 0.0;
266 
267  Eigen::Vector3d cop;
268  cop[0] = px;
269  cop[1] = py;
270  cop[2] = pz;
271 
272  return cop;
273 }
274 
275 /* ------------------------------------------------------------------- */
276 /* --- SIGNALS ------------------------------------------------------- */
277 /* ------------------------------------------------------------------- */
278 
279 DEFINE_SIGNAL_INNER_FUNCTION(kinematics_computations, int) {
280  if (!m_initSucceeded) {
281  SEND_WARNING_STREAM_MSG(
282  "Cannot compute signal kinematics_computations before initialization!");
283  return s;
284  }
285 
286  const Eigen::VectorXd& q = m_qSIN(iter);
287  assert(q.size() == m_model.nq && "Unexpected size of signal q");
288 
290 
291  pinocchio::forwardKinematics(m_model, m_data, q);
292  pinocchio::updateFramePlacement(m_model, m_data, m_left_foot_id);
293  pinocchio::updateFramePlacement(m_model, m_data, m_right_foot_id);
294 
295  m_contactLeft = m_data.oMf[m_left_foot_id] * m_ankle_M_sole;
296  m_contactRight = m_data.oMf[m_right_foot_id] * m_ankle_M_sole;
297 
299 
300  return s;
301 }
302 
303 void DistributeWrench::distributeWrench(const Eigen::VectorXd& wrenchDes,
304  const double rho, const double mu) {
305  // --- COSTS
306 
307  // Initialize cost matrices
308  Eigen::MatrixXd& Q = m_Q2;
309  Eigen::VectorXd& C = m_C2;
310 
311  // min |wrenchLeft + wrenchRight - wrenchDes|^2
312  Q.topLeftCorner<6, 6>().setIdentity();
313  Q.topRightCorner<6, 6>().setIdentity();
314  Q.bottomLeftCorner<6, 6>().setIdentity();
315  Q.bottomRightCorner<6, 6>().setIdentity();
316  Q *= m_wSum;
317 
318  C.head<6>() = -wrenchDes;
319  C.tail<6>() = -wrenchDes;
320  C *= m_wSum;
321 
322  // min |wrenchLeft_a|^2 + |wrenchRight_a|^2
323  Eigen::Matrix<double, 6, 6> tmp =
324  m_wAnkle.asDiagonal() *
325  m_data.oMf[m_left_foot_id].inverse().toDualActionMatrix();
326  Q.topLeftCorner<6, 6>().noalias() += tmp.transpose() * tmp * m_wNorm;
327 
328  tmp = m_wAnkle.asDiagonal() *
329  m_data.oMf[m_right_foot_id].inverse().toDualActionMatrix();
330  Q.bottomRightCorner<6, 6>().noalias() += tmp.transpose() * tmp * m_wNorm;
331 
332  // min |(1-rho)e_z^T*wrenchLeft_c - rho*e_z^T*wrenchLeft_c|
333  Eigen::Matrix<double, 1, 12> tmp2;
334  tmp2 << (1 - rho) * (m_contactLeft.inverse().toDualActionMatrix().row(2)),
335  (-rho) * (m_contactRight.inverse().toDualActionMatrix().row(2));
336 
337  Q.noalias() += tmp2.transpose() * tmp2 * m_wRatio;
338 
339  // --- Equality constraints
340 
341  Eigen::MatrixXd& Aeq = m_Aeq2;
342 
343  Eigen::VectorXd& Beq = m_Beq2;
344 
345  // --- Inequality constraints
346 
348 
349  Eigen::MatrixXd& Aineq = m_Aineq2;
350 
351  Aineq.topLeftCorner<16, 6>() =
352  m_wrenchFaceMatrix * m_contactLeft.inverse().toDualActionMatrix();
353  Aineq.topRightCorner<16, 6>().setZero();
354  Aineq.block<16, 6>(16, 0).setZero();
355  Aineq.block<16, 6>(16, 6) =
356  m_wrenchFaceMatrix * m_contactRight.inverse().toDualActionMatrix();
357 
358  Aineq.block<1, 6>(32, 0) =
359  -m_contactLeft.inverse().toDualActionMatrix().row(2);
360  Aineq.block<1, 6>(32, 6).setZero();
361  Aineq.block<1, 6>(33, 0).setZero();
362  Aineq.block<1, 6>(33, 6) =
363  -m_contactRight.inverse().toDualActionMatrix().row(2);
364 
365  Eigen::VectorXd& Bineq = m_Bineq2;
366 
367  Bineq.setZero();
368  Bineq(32) = -m_eps;
369  Bineq(33) = -m_eps;
370 
371  Eigen::VectorXd& result = m_result2;
372 
373  EiquadprogFast_status status =
374  m_qp2.solve_quadprog(Q, C, Aeq, -Beq, -Aineq, Bineq, result);
375 
376  m_emergency_stop_triggered = (status != EIQUADPROG_FAST_OPTIMAL);
377 
379  m_wrenchLeft.setZero(6);
380  m_wrenchRight.setZero(6);
381  } else {
382  m_wrenchLeft = result.head<6>();
383  m_wrenchRight = result.tail<6>();
384  }
385 }
386 
387 void DistributeWrench::saturateWrench(const Eigen::VectorXd& wrenchDes,
388  const int phase, const double mu) {
389  // Initialize cost matrices
390  Eigen::MatrixXd& Q = m_Q1;
391  Eigen::VectorXd& C = m_C1;
392 
393  // min |wrench - wrenchDes|^2
394  Q.setIdentity();
395  C = -wrenchDes;
396 
397  // --- Equality constraints
398 
399  Eigen::MatrixXd& Aeq = m_Aeq1;
400 
401  Eigen::VectorXd& Beq = m_Beq1;
402 
403  // --- Inequality constraints
404 
406 
407  Eigen::MatrixXd& Aineq = m_Aineq1;
408  if (phase > 0) {
409  Aineq = m_wrenchFaceMatrix * m_contactLeft.inverse().toDualActionMatrix();
410  } else {
411  Aineq = m_wrenchFaceMatrix * m_contactRight.inverse().toDualActionMatrix();
412  }
413 
414  Eigen::VectorXd& Bineq = m_Bineq1;
415  Bineq.setZero();
416 
417  Eigen::VectorXd& result = m_result1;
418 
419  EiquadprogFast_status status =
420  m_qp1.solve_quadprog(Q, C, Aeq, -Beq, -Aineq, Bineq, result);
421 
422  m_emergency_stop_triggered = (status != EIQUADPROG_FAST_OPTIMAL);
423 
425  m_wrenchLeft.setZero(6);
426  m_wrenchRight.setZero(6);
427  } else {
428  if (phase > 0) {
429  m_wrenchLeft = result;
430  m_wrenchRight.setZero(6);
431  } else if (phase < 0) {
432  m_wrenchRight = result;
433  m_wrenchLeft.setZero(6);
434  }
435  }
436 }
437 
438 DEFINE_SIGNAL_INNER_FUNCTION(qp_computations, int) {
439  if (!m_initSucceeded) {
440  SEND_WARNING_STREAM_MSG(
441  "Cannot compute signal qp_computations before initialization!");
442  return s;
443  }
444 
445  const Eigen::VectorXd& wrenchDes = m_wrenchDesSIN(iter);
446  const int& dummy = m_kinematics_computationsSINNER(iter);
447  (void)dummy;
448  const int& phase = m_phaseSIN(iter);
449 
450  const double& mu = m_frictionCoefficientSIN(iter); // 0.7
451 
452  assert(wrenchDes.size() == 6 && "Unexpected size of signal wrenchDes");
453 
454  getProfiler().start(PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS);
455 
456  if (phase == 0) {
457  const double& rho = m_rhoSIN(iter);
458 
459  m_wSum = m_wSumSIN(iter); // 10000.0
460  m_wNorm = m_wNormSIN(iter); // 10.0
461  m_wRatio = m_wRatioSIN(iter); // 1.0
462  m_wAnkle = m_wAnkleSIN(iter); // 1., 1., 1e-4, 1., 1., 1e-4
463 
464  distributeWrench(wrenchDes, rho, mu);
465  } else {
466  saturateWrench(wrenchDes, phase, mu);
467  }
468 
469  getProfiler().stop(PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS);
470 
471  if (m_emergency_stop_triggered) {
472  SEND_ERROR_STREAM_MSG("No solution to the QP problem!");
473  return s;
474  }
475 
476  return s;
477 }
478 
480  if (!m_initSucceeded) {
481  SEND_WARNING_STREAM_MSG(
482  "Cannot compute signal wrenchLeft before initialization!");
483  return s;
484  }
485  if (s.size() != 6) s.resize(6);
486 
487  const int& dummy = m_qp_computationsSINNER(iter);
488  (void)dummy;
489  s = m_wrenchLeft;
490  return s;
491 }
492 
494  if (!m_initSucceeded) {
495  SEND_WARNING_STREAM_MSG(
496  "Cannot compute signal wrenchRight before initialization!");
497  return s;
498  }
499  if (s.size() != 6) s.resize(6);
500 
501  const int& dummy = m_qp_computationsSINNER(iter);
502  (void)dummy;
503  s = m_wrenchRight;
504  return s;
505 }
506 
508  if (!m_initSucceeded) {
509  SEND_WARNING_STREAM_MSG(
510  "Cannot compute signal ankleWrenchLeft before initialization!");
511  return s;
512  }
513  if (s.size() != 6) s.resize(6);
514 
515  const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
516 
517  s = m_data.oMf[m_left_foot_id]
518  .actInv(pinocchio::Force(wrenchLeft))
519  .toVector();
520 
521  return s;
522 }
523 
525  if (!m_initSucceeded) {
526  SEND_WARNING_STREAM_MSG(
527  "Cannot compute signal ankleWrenchRight before initialization!");
528  return s;
529  }
530  if (s.size() != 6) s.resize(6);
531 
532  const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
533 
534  s = m_data.oMf[m_right_foot_id]
535  .actInv(pinocchio::Force(wrenchRight))
536  .toVector();
537 
538  return s;
539 }
540 
542  if (!m_initSucceeded) {
543  SEND_WARNING_STREAM_MSG(
544  "Cannot compute signal surfaceWrenchLeft before initialization!");
545  return s;
546  }
547  if (s.size() != 6) s.resize(6);
548 
549  const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
550 
551  s = m_contactLeft.actInv(pinocchio::Force(wrenchLeft)).toVector();
552 
553  return s;
554 }
555 
557  if (!m_initSucceeded) {
558  SEND_WARNING_STREAM_MSG(
559  "Cannot compute signal surfaceWrenchRight before initialization!");
560  return s;
561  }
562  if (s.size() != 6) s.resize(6);
563 
564  const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
565 
566  s = m_contactRight.actInv(pinocchio::Force(wrenchRight)).toVector();
567 
568  return s;
569 }
570 
572  if (!m_initSucceeded) {
573  SEND_WARNING_STREAM_MSG(
574  "Cannot compute signal copLeft before initialization!");
575  return s;
576  }
577  if (s.size() != 3) s.resize(3);
578 
579  const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
580 
581  if (m_emergency_stop_triggered) {
582  s.setZero(3);
583  return s;
584  }
585 
586  s = computeCoP(wrenchLeft, m_contactLeft);
587 
588  return s;
589 }
590 
592  if (!m_initSucceeded) {
593  SEND_WARNING_STREAM_MSG(
594  "Cannot compute signal copRight before initialization!");
595  return s;
596  }
597  if (s.size() != 3) s.resize(3);
598 
599  const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
600 
601  if (m_emergency_stop_triggered) {
602  s.setZero(3);
603  return s;
604  }
605 
606  s = computeCoP(wrenchRight, m_contactRight);
607 
608  return s;
609 }
610 
612  if (!m_initSucceeded) {
613  SEND_WARNING_STREAM_MSG(
614  "Cannot compute signal wrenchRef before initialization!");
615  return s;
616  }
617  if (s.size() != 6) s.resize(6);
618 
619  const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
620  const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
621 
622  s = wrenchLeft + wrenchRight;
623 
624  return s;
625 }
626 
628  if (!m_initSucceeded) {
629  SEND_WARNING_STREAM_MSG(
630  "Cannot compute signal zmpRef before initialization!");
631  return s;
632  }
633  if (s.size() != 3) s.resize(3);
634 
635  const Eigen::VectorXd& wrenchRef = m_wrenchRefSOUT(iter);
636 
637  if (m_emergency_stop_triggered) {
638  s.setZero(3);
639  return s;
640  }
641 
642  // const double fx = wrenchRef[0];
643  // const double fy = wrenchRef[1];
644  const double fz = wrenchRef[2];
645  const double tx = wrenchRef[3];
646  const double ty = wrenchRef[4];
647 
648  double m_eps = 0.1; // temporary
649 
650  double px, py;
651  if (fz >= m_eps / 2) {
652  px = -ty / fz;
653  py = tx / fz;
654  } else {
655  px = 0.0;
656  py = 0.0;
657  }
658  const double pz = 0.0;
659 
660  Eigen::Vector3d zmp(3);
661  zmp[0] = px;
662  zmp[1] = py;
663  zmp[2] = pz;
664 
665  s = zmp;
666 
667  return s;
668 }
669 
670 DEFINE_SIGNAL_OUT_FUNCTION(emergencyStop, bool) {
671  const dynamicgraph::Vector& zmp =
672  m_zmpRefSOUT(iter); // dummy to trigger zmp computation
673  (void)zmp; // disable unused variable warning
674  s = m_emergency_stop_triggered;
675  return s;
676 }
677 
678 /* --- COMMANDS ---------------------------------------------------------- */
679 
680 /* ------------------------------------------------------------------- */
681 /* --- ENTITY -------------------------------------------------------- */
682 /* ------------------------------------------------------------------- */
683 
684 void DistributeWrench::display(std::ostream& os) const {
685  os << "DistributeWrench " << getName();
686  try {
687  getProfiler().report_all(3, os);
688  } catch (ExceptionSignal e) {
689  }
690 }
691 
692 } // namespace talos_balance
693 } // namespace sot
694 } // namespace dynamicgraph
sot_talos_balance.test.appli_admittance_end_effector.q
list q
Definition: appli_admittance_end_effector.py:30
dynamicgraph::sot::talos_balance::DistributeWrench::m_wRatio
double m_wRatio
Definition: distribute-wrench.hh:168
INPUT_SIGNALS
#define INPUT_SIGNALS
Definition: distribute-wrench.cpp:45
dynamicgraph::sot::talos_balance::DistributeWrench::m_C1
Eigen::VectorXd m_C1
Definition: distribute-wrench.hh:144
dynamicgraph::sot::talos_balance::DistributeWrench::m_Bineq2
Eigen::VectorXd m_Bineq2
Definition: distribute-wrench.hh:162
sot_talos_balance.test.appli_admittance_end_effector.sot
sot
Definition: appli_admittance_end_effector.py:117
sot_talos_balance.test.appli_ankle_admittance.robotName
string robotName
Definition: appli_ankle_admittance.py:33
OUTPUT_SIGNALS
#define OUTPUT_SIGNALS
Definition: distribute-wrench.cpp:51
dynamicgraph::sot::talos_balance::DistributeWrench::set_left_foot_sizes
void set_left_foot_sizes(const dynamicgraph::Vector &s)
Definition: distribute-wrench.cpp:217
dynamicgraph::sot::talos_balance::DistributeWrench::m_Q1
Eigen::MatrixXd m_Q1
Definition: distribute-wrench.hh:143
dynamicgraph::sot::talos_balance::DistributeWrench::distributeWrench
void distributeWrench(const Eigen::VectorXd &wrenchDes, const double rho, const double mu)
Definition: distribute-wrench.cpp:303
dynamicgraph::sot::talos_balance::DistributeWrench::m_data
pinocchio::Data m_data
Pinocchio robot model.
Definition: distribute-wrench.hh:115
dynamicgraph
Definition: treeview.dox:24
dynamicgraph::sot::talos_balance::math::Vector6
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: fwd.hh:42
dynamicgraph::sot::talos_balance::DistributeWrench::m_left_foot_sizes
Eigen::Vector4d m_left_foot_sizes
Definition: distribute-wrench.hh:131
sot_talos_balance.talos.distribute_conf.wAnkle
list wAnkle
Definition: distribute_conf.py:13
dynamicgraph::sot::talos_balance::DistributeWrench::set_right_foot_sizes
void set_right_foot_sizes(const dynamicgraph::Vector &s)
Definition: distribute-wrench.cpp:209
dynamicgraph::sot::talos_balance::DistributeWrench::m_Beq1
Eigen::VectorXd m_Beq1
Definition: distribute-wrench.hh:147
PROFILE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS
#define PROFILE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS
Definition: distribute-wrench.cpp:38
sot_talos_balance.talos.distribute_conf.wNorm
float wNorm
Definition: distribute_conf.py:11
dynamicgraph::sot::talos_balance::DistributeWrench::m_emergency_stop_triggered
bool m_emergency_stop_triggered
Definition: distribute-wrench.hh:176
dynamicgraph::sot::talos_balance::DistributeWrench::m_Aeq2
Eigen::MatrixXd m_Aeq2
Definition: distribute-wrench.hh:158
dynamicgraph::sot::talos_balance::DistributeWrench::DistributeWrench
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DistributeWrench(const std::string &name)
Definition: distribute-wrench.cpp:68
dynamicgraph::sot::talos_balance::DistributeWrench::m_qp1
eiquadprog::solvers::EiquadprogFast m_qp1
Definition: distribute-wrench.hh:139
dynamicgraph::sot::talos_balance::DistributeWrench::computeCoP
Eigen::Vector3d computeCoP(const dynamicgraph::Vector &wrench, const pinocchio::SE3 &pose) const
Definition: distribute-wrench.cpp:241
sot_talos_balance.talos.distribute_conf.frictionCoefficient
float frictionCoefficient
Definition: distribute_conf.py:8
dynamicgraph::sot::talos_balance::DistributeWrench::m_Aineq2
Eigen::MatrixXd m_Aineq2
Definition: distribute-wrench.hh:161
dynamicgraph::sot::talos_balance::DistributeWrench::m_Q2
Eigen::MatrixXd m_Q2
Definition: distribute-wrench.hh:155
sot_talos_balance.talos.distribute_conf.wSum
float wSum
Definition: distribute_conf.py:10
dynamicgraph::sot::talos_balance::DistributeWrench::display
virtual void display(std::ostream &os) const
Definition: distribute-wrench.cpp:684
dynamicgraph::sot::talos_balance::DistributeWrench::m_wNorm
double m_wNorm
Definition: distribute-wrench.hh:167
dynamicgraph::sot::talos_balance::DistributeWrench::m_contactRight
pinocchio::SE3 m_contactRight
Definition: distribute-wrench.hh:126
PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS
#define PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS
Definition: distribute-wrench.cpp:40
dynamicgraph::sot::talos_balance::DistributeWrench::m_wrenchRight
Eigen::Matrix< double, 6, 1 > m_wrenchRight
Definition: distribute-wrench.hh:129
dynamicgraph::sot::talos_balance::DistributeWrench::m_wrenchFaceMatrix
Eigen::Matrix< double, 16, 6 > m_wrenchFaceMatrix
Definition: distribute-wrench.hh:137
dynamicgraph::sot::talos_balance::DistributeWrench::m_result1
Eigen::VectorXd m_result1
Definition: distribute-wrench.hh:152
dynamicgraph::sot::talos_balance::DistributeWrench::m_ankle_M_sole
pinocchio::SE3 m_ankle_M_sole
Definition: distribute-wrench.hh:120
dynamicgraph::sot::talos_balance::DistributeWrench::m_wrenchLeft
Eigen::Matrix< double, 6, 1 > m_wrenchLeft
Definition: distribute-wrench.hh:128
sot_talos_balance.talos.balance_ctrl_conf.mu
mu
Definition: balance_ctrl_conf.py:71
dynamicgraph::sot::talos_balance::DEFINE_SIGNAL_OUT_FUNCTION
DEFINE_SIGNAL_OUT_FUNCTION(dq, dynamicgraph::Vector)
Definition: admittance-controller-end-effector.cpp:210
dynamicgraph::sot::talos_balance::DistributeWrench::m_model
pinocchio::Model m_model
true if the entity has been successfully initialized
Definition: distribute-wrench.hh:114
dynamicgraph::sot::talos_balance::DistributeWrench::computeWrenchFaceMatrix
void computeWrenchFaceMatrix(const double mu)
Definition: distribute-wrench.cpp:226
dynamicgraph::sot::talos_balance::DistributeWrench::m_Aeq1
Eigen::MatrixXd m_Aeq1
Definition: distribute-wrench.hh:146
dynamicgraph::sot::talos_balance::DistributeWrench::saturateWrench
void saturateWrench(const Eigen::VectorXd &wrenchDes, const int phase, const double mu)
Definition: distribute-wrench.cpp:387
dynamicgraph::sot::talos_balance::DistributeWrench::m_C2
Eigen::VectorXd m_C2
Definition: distribute-wrench.hh:156
dynamicgraph::sot::talos_balance::DistributeWrench::m_right_foot_id
pinocchio::FrameIndex m_right_foot_id
Definition: distribute-wrench.hh:123
dynamicgraph::sot::talos_balance::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hh:36
sot_talos_balance.test.script_test_end_effector.wrench
wrench
Definition: script_test_end_effector.py:9
dynamicgraph::sot::talos_balance::DistributeWrench::m_Beq2
Eigen::VectorXd m_Beq2
Definition: distribute-wrench.hh:159
dynamicgraph::sot::talos_balance::DistributeWrench::m_wAnkle
Eigen::VectorXd m_wAnkle
Definition: distribute-wrench.hh:169
WEIGHT_SIGNALS
#define WEIGHT_SIGNALS
Definition: distribute-wrench.cpp:43
dynamicgraph::sot::talos_balance::DistributeWrench::m_right_foot_sizes
Eigen::Vector4d m_right_foot_sizes
Definition: distribute-wrench.hh:133
dynamicgraph::sot::talos_balance::DistributeWrench::m_robot_util
RobotUtilShrPtr m_robot_util
Pinocchio robot data.
Definition: distribute-wrench.hh:116
dynamicgraph::sot::talos_balance::DistributeWrench::m_Aineq1
Eigen::MatrixXd m_Aineq1
Definition: distribute-wrench.hh:149
dynamicgraph::sot::talos_balance::DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
dynamicgraph::sot::talos_balance::DistributeWrench::m_Bineq1
Eigen::VectorXd m_Bineq1
Definition: distribute-wrench.hh:150
dynamicgraph::sot::talos_balance::DistributeWrench::m_initSucceeded
bool m_initSucceeded
Definition: distribute-wrench.hh:113
dynamicgraph::sot::talos_balance::DistributeWrench::m_result2
Eigen::VectorXd m_result2
Definition: distribute-wrench.hh:164
sot_talos_balance.talos.distribute_conf.wRatio
float wRatio
Definition: distribute_conf.py:12
dynamicgraph::sot::talos_balance::DEFINE_SIGNAL_INNER_FUNCTION
DEFINE_SIGNAL_INNER_FUNCTION(w_force, dynamicgraph::Vector)
Definition: admittance-controller-end-effector.cpp:145
dynamicgraph::sot::talos_balance::DistributeWrench::m_qp2
eiquadprog::solvers::EiquadprogFast m_qp2
Definition: distribute-wrench.hh:140
dynamicgraph::sot::talos_balance::EntityClassName
AdmittanceControllerEndEffector EntityClassName
Definition: admittance-controller-end-effector.cpp:46
dynamicgraph::sot::talos_balance::DistributeWrench::m_left_foot_id
pinocchio::FrameIndex m_left_foot_id
ankle to sole transformation
Definition: distribute-wrench.hh:122
sot_talos_balance.test.appli_ankle_admittance.h
h
Definition: appli_ankle_admittance.py:37
sot_talos_balance.test.appli_dcm_zmp_control.name
name
Definition: appli_dcm_zmp_control.py:298
dynamicgraph::sot::talos_balance::DistributeWrench::m_eps
double m_eps
Definition: distribute-wrench.hh:109
dynamicgraph::sot::talos_balance::DistributeWrench::m_wSum
double m_wSum
Definition: distribute-wrench.hh:166
distribute-wrench.hh
dynamicgraph::sot::talos_balance::DistributeWrench::m_contactLeft
pinocchio::SE3 m_contactLeft
Definition: distribute-wrench.hh:125
dynamicgraph::sot::talos_balance::DistributeWrench::init
void init(const std::string &robotName)
Definition: distribute-wrench.cpp:157