19 #include <dynamic-graph/all-commands.h>
20 #include <dynamic-graph/factory.h>
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>
31 namespace talos_balance {
32 namespace dg = ::dynamicgraph;
34 using namespace dg::command;
35 using namespace eiquadprog::solvers;
38 #define PROFILE_DISTRIBUTE_WRENCH_KINEMATICS_COMPUTATIONS \
39 "DistributeWrench: kinematics computations "
40 #define PROFILE_DISTRIBUTE_WRENCH_QP_COMPUTATIONS \
41 "DistributeWrench: QP problem computations "
43 #define WEIGHT_SIGNALS m_wSumSIN << m_wNormSIN << m_wRatioSIN << m_wAnkleSIN
45 #define INPUT_SIGNALS \
46 m_wrenchDesSIN << m_qSIN << m_rhoSIN << m_phaseSIN \
47 << m_frictionCoefficientSIN << WEIGHT_SIGNALS
49 #define INNER_SIGNALS m_kinematics_computations << m_qp_computations
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
72 CONSTRUCT_SIGNAL_IN(rho, double),
73 CONSTRUCT_SIGNAL_IN(phase, int),
75 CONSTRUCT_SIGNAL_IN(
wSum, double),
76 CONSTRUCT_SIGNAL_IN(
wNorm, double),
77 CONSTRUCT_SIGNAL_IN(
wRatio, double),
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),
85 m_qp_computationsSINNER),
92 m_qp_computationsSINNER),
99 m_wrenchLeftSOUT << m_wrenchRightSOUT),
101 CONSTRUCT_SIGNAL_OUT(emergencyStop, bool, m_zmpRefSOUT),
102 m_initSucceeded(false),
104 m_data(pinocchio::Model()),
122 m_qp1.reset(6, 0, 16);
123 m_qp2.reset(12, 0, 34);
127 docCommandVoid1(
"Initialize the entity.",
131 "set_right_foot_sizes",
135 "Set the size of the right foot (pos x, neg x, pos y, neg y)",
138 "set_left_foot_sizes",
142 "Set the size of the left foot (pos x, neg x, pos y, neg y)",
147 makeDirectGetter(*
this, &
m_eps,
148 docDirectGetter(
"Get minimum pressure",
"double")));
151 makeDirectSetter(*
this, &
m_eps,
152 docDirectSetter(
"Set minimum pressure",
"double")));
158 if (!m_wrenchDesSIN.isPlugged())
159 return SEND_MSG(
"Init failed: signal wrenchDes is not plugged",
161 if (!m_qSIN.isPlugged())
162 return SEND_MSG(
"Init failed: signal q is not plugged", MSG_TYPE_ERROR);
165 return SEND_ERROR_STREAM_MSG(
166 "Init failed: left foot size is not initialized");
168 return SEND_ERROR_STREAM_MSG(
169 "Init failed: right foot size is not initialized");
174 if (isNameInRobotUtil(localName)) {
178 SEND_MSG(
"You should have a robotUtil pointer initialized before",
183 pinocchio::urdf::buildModel(
m_robot_util->m_urdf_filename,
184 pinocchio::JointModelFreeFlyer(),
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,
203 pinocchio::SE3(Eigen::Matrix3d::Identity(),
204 m_robot_util->m_foot_util.m_Right_Foot_Sole_XYZ.head<3>());
212 "Foot size vector should have size 4, not " + toString(s.size()),
220 "Foot size vector should have size 4, not " + toString(s.size()),
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,
242 const pinocchio::SE3& pose)
const {
244 pose.actInv(pinocchio::Force(wrenchGlobal)).toVector();
246 const double h = pose.translation()[2];
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];
258 if (fz >=
m_eps / 2) {
259 px = (-ty - fx *
h) / fz;
260 py = (tx - fy *
h) / fz;
265 const double pz = 0.0;
280 if (!m_initSucceeded) {
281 SEND_WARNING_STREAM_MSG(
282 "Cannot compute signal kinematics_computations before initialization!");
286 const Eigen::VectorXd&
q = m_qSIN(iter);
287 assert(
q.size() == m_model.nq &&
"Unexpected size of signal q");
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);
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;
304 const double rho,
const double mu) {
308 Eigen::MatrixXd& Q =
m_Q2;
309 Eigen::VectorXd& C =
m_C2;
312 Q.topLeftCorner<6, 6>().setIdentity();
313 Q.topRightCorner<6, 6>().setIdentity();
314 Q.bottomLeftCorner<6, 6>().setIdentity();
315 Q.bottomRightCorner<6, 6>().setIdentity();
318 C.head<6>() = -wrenchDes;
319 C.tail<6>() = -wrenchDes;
323 Eigen::Matrix<double, 6, 6> tmp =
326 Q.topLeftCorner<6, 6>().noalias() += tmp.transpose() * tmp *
m_wNorm;
330 Q.bottomRightCorner<6, 6>().noalias() += tmp.transpose() * tmp *
m_wNorm;
333 Eigen::Matrix<double, 1, 12> tmp2;
334 tmp2 << (1 - rho) * (
m_contactLeft.inverse().toDualActionMatrix().row(2)),
337 Q.noalias() += tmp2.transpose() * tmp2 *
m_wRatio;
341 Eigen::MatrixXd& Aeq =
m_Aeq2;
343 Eigen::VectorXd& Beq =
m_Beq2;
351 Aineq.topLeftCorner<16, 6>() =
353 Aineq.topRightCorner<16, 6>().setZero();
354 Aineq.block<16, 6>(16, 0).setZero();
355 Aineq.block<16, 6>(16, 6) =
358 Aineq.block<1, 6>(32, 0) =
360 Aineq.block<1, 6>(32, 6).setZero();
361 Aineq.block<1, 6>(33, 0).setZero();
362 Aineq.block<1, 6>(33, 6) =
373 EiquadprogFast_status status =
374 m_qp2.solve_quadprog(Q, C, Aeq, -Beq, -Aineq, Bineq, result);
388 const int phase,
const double mu) {
390 Eigen::MatrixXd& Q =
m_Q1;
391 Eigen::VectorXd& C =
m_C1;
399 Eigen::MatrixXd& Aeq =
m_Aeq1;
401 Eigen::VectorXd& Beq =
m_Beq1;
419 EiquadprogFast_status status =
420 m_qp1.solve_quadprog(Q, C, Aeq, -Beq, -Aineq, Bineq, result);
431 }
else if (phase < 0) {
439 if (!m_initSucceeded) {
440 SEND_WARNING_STREAM_MSG(
441 "Cannot compute signal qp_computations before initialization!");
445 const Eigen::VectorXd& wrenchDes = m_wrenchDesSIN(iter);
446 const int& dummy = m_kinematics_computationsSINNER(iter);
448 const int& phase = m_phaseSIN(iter);
450 const double&
mu = m_frictionCoefficientSIN(iter);
452 assert(wrenchDes.size() == 6 &&
"Unexpected size of signal wrenchDes");
457 const double& rho = m_rhoSIN(iter);
459 m_wSum = m_wSumSIN(iter);
460 m_wNorm = m_wNormSIN(iter);
461 m_wRatio = m_wRatioSIN(iter);
462 m_wAnkle = m_wAnkleSIN(iter);
464 distributeWrench(wrenchDes, rho,
mu);
466 saturateWrench(wrenchDes, phase,
mu);
471 if (m_emergency_stop_triggered) {
472 SEND_ERROR_STREAM_MSG(
"No solution to the QP problem!");
480 if (!m_initSucceeded) {
481 SEND_WARNING_STREAM_MSG(
482 "Cannot compute signal wrenchLeft before initialization!");
485 if (s.size() != 6) s.resize(6);
487 const int& dummy = m_qp_computationsSINNER(iter);
494 if (!m_initSucceeded) {
495 SEND_WARNING_STREAM_MSG(
496 "Cannot compute signal wrenchRight before initialization!");
499 if (s.size() != 6) s.resize(6);
501 const int& dummy = m_qp_computationsSINNER(iter);
508 if (!m_initSucceeded) {
509 SEND_WARNING_STREAM_MSG(
510 "Cannot compute signal ankleWrenchLeft before initialization!");
513 if (s.size() != 6) s.resize(6);
515 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
517 s = m_data.oMf[m_left_foot_id]
518 .actInv(pinocchio::Force(wrenchLeft))
525 if (!m_initSucceeded) {
526 SEND_WARNING_STREAM_MSG(
527 "Cannot compute signal ankleWrenchRight before initialization!");
530 if (s.size() != 6) s.resize(6);
532 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
534 s = m_data.oMf[m_right_foot_id]
535 .actInv(pinocchio::Force(wrenchRight))
542 if (!m_initSucceeded) {
543 SEND_WARNING_STREAM_MSG(
544 "Cannot compute signal surfaceWrenchLeft before initialization!");
547 if (s.size() != 6) s.resize(6);
549 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
551 s = m_contactLeft.actInv(pinocchio::Force(wrenchLeft)).toVector();
557 if (!m_initSucceeded) {
558 SEND_WARNING_STREAM_MSG(
559 "Cannot compute signal surfaceWrenchRight before initialization!");
562 if (s.size() != 6) s.resize(6);
564 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
566 s = m_contactRight.actInv(pinocchio::Force(wrenchRight)).toVector();
572 if (!m_initSucceeded) {
573 SEND_WARNING_STREAM_MSG(
574 "Cannot compute signal copLeft before initialization!");
577 if (s.size() != 3) s.resize(3);
579 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
581 if (m_emergency_stop_triggered) {
586 s = computeCoP(wrenchLeft, m_contactLeft);
592 if (!m_initSucceeded) {
593 SEND_WARNING_STREAM_MSG(
594 "Cannot compute signal copRight before initialization!");
597 if (s.size() != 3) s.resize(3);
599 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
601 if (m_emergency_stop_triggered) {
606 s = computeCoP(wrenchRight, m_contactRight);
612 if (!m_initSucceeded) {
613 SEND_WARNING_STREAM_MSG(
614 "Cannot compute signal wrenchRef before initialization!");
617 if (s.size() != 6) s.resize(6);
619 const Eigen::VectorXd& wrenchLeft = m_wrenchLeftSOUT(iter);
620 const Eigen::VectorXd& wrenchRight = m_wrenchRightSOUT(iter);
622 s = wrenchLeft + wrenchRight;
628 if (!m_initSucceeded) {
629 SEND_WARNING_STREAM_MSG(
630 "Cannot compute signal zmpRef before initialization!");
633 if (s.size() != 3) s.resize(3);
635 const Eigen::VectorXd& wrenchRef = m_wrenchRefSOUT(iter);
637 if (m_emergency_stop_triggered) {
644 const double fz = wrenchRef[2];
645 const double tx = wrenchRef[3];
646 const double ty = wrenchRef[4];
651 if (fz >= m_eps / 2) {
658 const double pz = 0.0;
660 Eigen::Vector3d zmp(3);
674 s = m_emergency_stop_triggered;
685 os <<
"DistributeWrench " << getName();
687 getProfiler().report_all(3, os);
688 }
catch (ExceptionSignal e) {