tsid-formulation.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS, NYU, MPI Tübingen
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid 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 GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #include <iostream>
19 
20 #include <boost/test/unit_test.hpp>
21 #include <boost/utility/binary.hpp>
22 
31 #include <tsid/solvers/solver-HQP-factory.hxx>
32 #include <tsid/solvers/utils.hpp>
35 #include <tsid/math/utils.hpp>
36 
37 #include <pinocchio/algorithm/joint-configuration.hpp> // integrate
38 #include <pinocchio/parsers/srdf.hpp>
39 
40 using namespace tsid;
41 using namespace tsid::trajectories;
42 using namespace tsid::math;
43 using namespace tsid::contacts;
44 using namespace tsid::tasks;
45 using namespace tsid::solvers;
46 using namespace tsid::robots;
47 using namespace std;
48 
49 #define REQUIRE_FINITE(A) BOOST_REQUIRE_MESSAGE(isFinite(A), #A << ": " << A)
50 #define CHECK_LESS_THAN(A, B) \
51  BOOST_CHECK_MESSAGE(A < B, #A << ": " << A << ">" << B)
52 
53 #define REQUIRE_TASK_FINITE(task) \
54  REQUIRE_FINITE(task.getConstraint().matrix()); \
55  REQUIRE_FINITE(task.getConstraint().vector())
56 
57 #define REQUIRE_CONTACT_FINITE(contact) \
58  REQUIRE_FINITE(contact.getMotionConstraint().matrix()); \
59  REQUIRE_FINITE(contact.getMotionConstraint().vector()); \
60  REQUIRE_FINITE(contact.getForceConstraint().matrix()); \
61  REQUIRE_FINITE(contact.getForceConstraint().lowerBound()); \
62  REQUIRE_FINITE(contact.getForceConstraint().upperBound()); \
63  REQUIRE_FINITE(contact.getForceRegularizationTask().matrix()); \
64  REQUIRE_FINITE(contact.getForceRegularizationTask().vector())
65 
66 const string romeo_model_path = TSID_SOURCE_DIR "/models/romeo";
67 const string quadruped_model_path = TSID_SOURCE_DIR "/models/quadruped";
68 
69 #ifndef NDEBUG
70 const int max_it = 10;
71 #else
72 const int max_it = 10;
73 #endif
74 
75 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
76 
78  public:
79  static const double lxp;
80  static const double lxn;
81  static const double lyp;
82  static const double lyn;
83  static const double lz;
84  static const double mu;
85  static const double fMin;
86  static const double fMax;
87  static const std::string rf_frame_name;
88  static const std::string lf_frame_name;
89  static const Vector3 contactNormal;
90  static const double w_com;
91  static const double w_posture;
92  static const double w_forceReg;
93  static const double kp_contact;
94  static const double kp_com;
95  static const double kp_posture;
96  double t;
97 
98  std::shared_ptr<RobotWrapper> robot;
99  std::shared_ptr<InverseDynamicsFormulationAccForce> tsid;
100  std::shared_ptr<Contact6d> contactRF;
101  std::shared_ptr<Contact6d> contactLF;
102  std::shared_ptr<TaskComEquality> comTask;
103  std::shared_ptr<TaskJointPosture> postureTask;
104  std::shared_ptr<TaskJointBounds> jointBoundsTask;
109 
110  StandardRomeoInvDynCtrl(double dt) : t(0.) {
111  vector<string> package_dirs;
112  package_dirs.push_back(romeo_model_path);
113  const string urdfFileName = package_dirs[0] + "/urdf/romeo.urdf";
114  robot = std::make_shared<RobotWrapper>(urdfFileName, package_dirs,
116 
117  const string srdfFileName = package_dirs[0] + "/srdf/romeo_collision.srdf";
118 
120  false);
121 
122  const unsigned int nv{static_cast<unsigned int>(robot->nv())};
123  q = neutral(robot->model());
124  std::cout << "q: " << q.transpose() << std::endl;
125  q(2) += 0.84;
126  v = Vector::Zero(nv);
127  BOOST_REQUIRE(robot->model().existFrame(rf_frame_name));
128  BOOST_REQUIRE(robot->model().existFrame(lf_frame_name));
129 
130  // Create the inverse-dynamics formulation
131  tsid = std::make_shared<InverseDynamicsFormulationAccForce>("tsid", *robot);
132  tsid->computeProblemData(t, q, v);
133  pinocchio::Data &data = tsid->data();
134 
135  // Add the contact constraints
136  Matrix3x contactPoints(3, 4);
137  contactPoints << -lxn, -lxn, +lxp, +lxp, -lyn, +lyp, -lyn, +lyp, lz, lz, lz,
138  lz;
139  contactRF = std::make_shared<Contact6d>("contact_rfoot", *robot,
140  rf_frame_name, contactPoints,
142  contactRF->Kp(kp_contact * Vector::Ones(6));
143  contactRF->Kd(2.0 * contactRF->Kp().cwiseSqrt());
144  H_rf_ref = robot->position(data, robot->model().getJointId(rf_frame_name));
145  contactRF->setReference(H_rf_ref);
146  tsid->addRigidContact(*contactRF, w_forceReg);
147 
148  contactLF = std::make_shared<Contact6d>("contact_lfoot", *robot,
149  lf_frame_name, contactPoints,
151  contactLF->Kp(kp_contact * Vector::Ones(6));
152  contactLF->Kd(2.0 * contactLF->Kp().cwiseSqrt());
153  H_lf_ref = robot->position(data, robot->model().getJointId(lf_frame_name));
154  contactLF->setReference(H_lf_ref);
155  tsid->addRigidContact(*contactLF, w_forceReg);
156 
157  // Add the com task
158  comTask = std::make_shared<TaskComEquality>("task-com", *robot);
159  comTask->Kp(kp_com * Vector::Ones(3));
160  comTask->Kd(2.0 * comTask->Kp().cwiseSqrt());
161  tsid->addMotionTask(*comTask, w_com, 1);
162 
163  // Add the posture task
164  postureTask = std::make_shared<TaskJointPosture>("task-posture", *robot);
165  postureTask->Kp(kp_posture * Vector::Ones(nv - 6));
166  postureTask->Kd(2.0 * postureTask->Kp().cwiseSqrt());
167  tsid->addMotionTask(*postureTask, w_posture, 1);
168 
169  // Add the joint bounds task
170  jointBoundsTask =
171  std::make_shared<TaskJointBounds>("task-joint-bounds", *robot, dt);
172  Vector dq_max = 10 * Vector::Ones(robot->na());
173  Vector dq_min = -dq_max;
174  jointBoundsTask->setVelocityBounds(dq_min, dq_max);
175  tsid->addMotionTask(*jointBoundsTask, 1.0, 0);
176  }
177 };
178 
179 const double StandardRomeoInvDynCtrl::lxp = 0.14;
180 const double StandardRomeoInvDynCtrl::lxn = 0.077;
181 const double StandardRomeoInvDynCtrl::lyp = 0.069;
182 const double StandardRomeoInvDynCtrl::lyn = 0.069;
183 const double StandardRomeoInvDynCtrl::lz = 0.105;
184 const double StandardRomeoInvDynCtrl::mu = 0.3;
185 const double StandardRomeoInvDynCtrl::fMin = 5.0;
186 const double StandardRomeoInvDynCtrl::fMax = 1000.0;
187 const std::string StandardRomeoInvDynCtrl::rf_frame_name = "RAnkleRoll";
188 const std::string StandardRomeoInvDynCtrl::lf_frame_name = "LAnkleRoll";
189 const Vector3 StandardRomeoInvDynCtrl::contactNormal = Vector3::UnitZ();
190 const double StandardRomeoInvDynCtrl::w_com = 1.0;
191 const double StandardRomeoInvDynCtrl::w_posture = 1e-2;
192 const double StandardRomeoInvDynCtrl::w_forceReg = 1e-5;
193 const double StandardRomeoInvDynCtrl::kp_contact = 100.0;
194 const double StandardRomeoInvDynCtrl::kp_com = 30.0;
195 const double StandardRomeoInvDynCtrl::kp_posture = 30.0;
196 
197 BOOST_AUTO_TEST_CASE(test_invdyn_formulation_acc_force_remove_contact) {
198  cout << "\n*** test_invdyn_formulation_acc_force_remove_contact ***\n";
199  const double dt = 0.01;
200  const unsigned int PRINT_N = 10;
201  const unsigned int REMOVE_CONTACT_N = 100;
202  const double CONTACT_TRANSITION_TIME = 1.0;
203  const double kp_RF = 100.0;
204  const double w_RF = 1e3;
205  double t = 0.0;
206 
207  StandardRomeoInvDynCtrl romeo_inv_dyn(dt);
208  RobotWrapper &robot = *(romeo_inv_dyn.robot);
209  auto tsid = romeo_inv_dyn.tsid;
210  Contact6d &contactRF = *(romeo_inv_dyn.contactRF);
211  Contact6d &contactLF = *(romeo_inv_dyn.contactLF);
212  TaskComEquality &comTask = *(romeo_inv_dyn.comTask);
213  TaskJointPosture &postureTask = *(romeo_inv_dyn.postureTask);
214  Vector q = romeo_inv_dyn.q;
215  Vector v = romeo_inv_dyn.v;
216  const int nv = robot.model().nv;
217 
218  // Add the right foot task
219  auto rightFootTask = std::make_shared<TaskSE3Equality>(
220  "task-right-foot", robot, romeo_inv_dyn.rf_frame_name);
221  rightFootTask->Kp(kp_RF * Vector::Ones(6));
222  rightFootTask->Kd(2.0 * rightFootTask->Kp().cwiseSqrt());
223  pinocchio::SE3 H_rf_ref = robot.position(
224  tsid->data(), robot.model().getJointId(romeo_inv_dyn.rf_frame_name));
225  tsid->addMotionTask(*rightFootTask, w_RF, 1);
226 
227  rightFootTask->setReference(H_rf_ref);
228 
229  Vector3 com_ref = robot.com(tsid->data());
230  com_ref(1) += 0.1;
231  auto trajCom =
232  std::make_shared<TrajectoryEuclidianConstant>("traj_com", com_ref);
234 
235  Vector q_ref = q.tail(nv - 6);
236  auto trajPosture =
237  std::make_shared<TrajectoryEuclidianConstant>("traj_posture", q_ref);
239 
240  // Create an HQP solver
241  SolverHQPBase *solver = SolverHQPFactory::createNewSolver(
242  SOLVER_HQP_EIQUADPROG, "solver-eiquadprog");
243  solver->resize(tsid->nVar(), tsid->nEq(), tsid->nIn());
244 
245  Vector tau_old(nv - 6);
246  for (int i = 0; i < max_it; i++) {
247  if (i == REMOVE_CONTACT_N) {
248  cout << "Start breaking contact right foot\n";
249  tsid->removeRigidContact(contactRF.name(), CONTACT_TRANSITION_TIME);
250  }
251 
252  sampleCom = trajCom->computeNext();
253  comTask.setReference(sampleCom);
254  samplePosture = trajPosture->computeNext();
255  postureTask.setReference(samplePosture);
256 
257  const HQPData &HQPData = tsid->computeProblemData(t, q, v);
258  if (i == 0) cout << HQPDataToString(HQPData, false) << endl;
259 
264 
265  CHECK_LESS_THAN(contactRF.getMotionTask().position_error().norm(), 1e-3);
266  CHECK_LESS_THAN(contactLF.getMotionTask().position_error().norm(), 1e-3);
267 
268  const HQPOutput &sol = solver->solve(HQPData);
269 
270  BOOST_CHECK_MESSAGE(sol.status == HQP_STATUS_OPTIMAL,
271  "Status " + toString(sol.status));
272 
273  const Vector &tau = tsid->getActuatorForces(sol);
274  const Vector &dv = tsid->getAccelerations(sol);
275 
276  if (i > 0) {
277  CHECK_LESS_THAN((tau - tau_old).norm(), 2e1);
278  if ((tau - tau_old).norm() > 2e1) // || (i>=197 && i<=200))
279  {
280  // contactRF.computeMotionTask(t, q, v, tsid->data());
281  // rightFootTask->compute(t, q, v, tsid->data());
282  cout << "Time " << i << endl;
283  cout << "tau:\n"
284  << tau.transpose() << "\ntauOld:\n"
285  << tau_old.transpose() << "\n";
286  // cout << "RF contact task des acc:
287  // "<<contactRF.getMotionTask().getDesiredAcceleration().transpose()<<endl;
288  // cout << "RF contact task acc:
289  // "<<contactRF.getMotionTask().getAcceleration(dv).transpose()<<endl;
290  // cout << "RF motion task des acc:
291  // "<<rightFootTask->getDesiredAcceleration().transpose()<<endl;
292  cout << endl;
293  }
294  }
295  tau_old = tau;
296 
297  if (i % PRINT_N == 0) {
298  cout << "Time " << i << endl;
299 
300  Eigen::Matrix<double, 12, 1> f;
301  if (tsid->getContactForces(contactRF.name(), sol, f))
302  cout << " " << contactRF.name()
303  << " force: " << contactRF.getNormalForce(f) << " \t";
304 
305  if (tsid->getContactForces(contactLF.name(), sol, f))
306  cout << " " << contactLF.name()
307  << " force: " << contactLF.getNormalForce(f) << " \t";
308 
309  cout << comTask.name() << " err: " << comTask.position_error().norm()
310  << " \t";
311  cout << "v=" << v.norm() << "\t dv=" << dv.norm() << endl;
312  }
313 
314  v += dt * dv;
315  q = pinocchio::integrate(robot.model(), q, dt * v);
316  t += dt;
317 
318  REQUIRE_FINITE(dv.transpose());
319  REQUIRE_FINITE(v.transpose());
320  REQUIRE_FINITE(q.transpose());
321  CHECK_LESS_THAN(dv.norm(), 1e6);
322  CHECK_LESS_THAN(v.norm(), 1e6);
323  }
324 
325  delete solver;
326  cout << "\n### TEST FINISHED ###\n";
327  PRINT_VECTOR(v);
328  cout << "Final CoM position: " << robot.com(tsid->data()).transpose()
329  << endl;
330  cout << "Desired CoM position: " << com_ref.transpose() << endl;
331 }
332 
333 BOOST_AUTO_TEST_CASE(test_invdyn_formulation_acc_force) {
334  cout << "\n*** test_invdyn_formulation_acc_force ***\n";
335 
336  const double dt = 0.001;
337  const unsigned int PRINT_N = 100;
338  double t = 0.0;
339 
340  StandardRomeoInvDynCtrl romeo_inv_dyn(dt);
341  RobotWrapper &robot = *(romeo_inv_dyn.robot);
342  auto tsid = romeo_inv_dyn.tsid;
343  Contact6d &contactRF = *(romeo_inv_dyn.contactRF);
344  Contact6d &contactLF = *(romeo_inv_dyn.contactLF);
345  TaskComEquality &comTask = *(romeo_inv_dyn.comTask);
346  TaskJointPosture &postureTask = *(romeo_inv_dyn.postureTask);
347  Vector q = romeo_inv_dyn.q;
348  Vector v = romeo_inv_dyn.v;
349  const int nv = robot.model().nv;
350 
351  Vector3 com_ref = robot.com(tsid->data());
352  com_ref(1) += 0.1;
353  auto trajCom =
354  std::make_shared<TrajectoryEuclidianConstant>("traj_com", com_ref);
356 
357  Vector q_ref = q.tail(nv - 6);
358  auto trajPosture =
359  std::make_shared<TrajectoryEuclidianConstant>("traj_posture", q_ref);
361 
362  // Create an HQP solver
363  SolverHQPBase *solver = SolverHQPFactory::createNewSolver(
364  SOLVER_HQP_EIQUADPROG, "solver-eiquadprog");
365 
366  solver->resize(tsid->nVar(), tsid->nEq(), tsid->nIn());
367  cout << "nVar " << tsid->nVar() << endl;
368  cout << "nEq " << tsid->nEq() << endl;
369  cout << "nIn " << tsid->nIn() << endl;
370  cout << "Initial CoM position: " << robot.com(tsid->data()).transpose()
371  << endl;
372  cout << "Initial RF position: " << romeo_inv_dyn.H_rf_ref << endl;
373  cout << "Initial LF position: " << romeo_inv_dyn.H_lf_ref << endl;
374 
375  Vector dv = Vector::Zero(nv);
376  Vector f_RF(12), f_LF(12), f(24);
377  vector<ContactBase *> contacts;
378  contacts.push_back(&contactRF);
379  contacts.push_back(&contactLF);
380  Matrix Jc(24, nv);
381  for (int i = 0; i < max_it; i++) {
382  sampleCom = trajCom->computeNext();
383  comTask.setReference(sampleCom);
384  samplePosture = trajPosture->computeNext();
385  postureTask.setReference(samplePosture);
386 
387  const HQPData &HQPData = tsid->computeProblemData(t, q, v);
388  if (i == 0) cout << HQPDataToString(HQPData, false) << endl;
389 
394 
395  CHECK_LESS_THAN(contactRF.getMotionTask().position_error().norm(), 1e-3);
396  CHECK_LESS_THAN(contactLF.getMotionTask().position_error().norm(), 1e-3);
397 
398  if (contactRF.getMotionTask().position_error().norm() > 1e-2) {
399  PRINT_VECTOR(v);
400  PRINT_VECTOR(dv);
401  Vector rf_pos = contactRF.getMotionTask().position();
402  Vector rf_pos_ref = contactRF.getMotionTask().position_ref();
403  pinocchio::SE3 M_rf, M_rf_ref;
404  vectorToSE3(rf_pos, M_rf);
405  vectorToSE3(rf_pos_ref, M_rf_ref);
406  cout << "RF pos: " << rf_pos.transpose() << endl;
407  cout << "RF pos ref: " << rf_pos_ref.transpose() << endl;
408  }
409 
410  if (i % PRINT_N == 0) {
411  cout << "Time " << i << endl;
412  cout << " " << contactRF.name()
413  << " err: " << contactRF.getMotionTask().position_error().norm()
414  << " \t";
415  cout << contactLF.name()
416  << " err: " << contactLF.getMotionTask().position_error().norm()
417  << " \t";
418  cout << comTask.name() << " err: " << comTask.position_error().norm()
419  << " \t";
420  cout << postureTask.name()
421  << " err: " << postureTask.position_error().norm() << " \t";
422  cout << "v=" << v.norm() << "\t dv=" << dv.norm() << endl;
423  // PRINT_VECTOR(postureTask.getConstraint().vector());
424  // PRINT_VECTOR(postureTask.position_error());
425  if (i < 20) PRINT_VECTOR(dv);
426  }
427 
428  const HQPOutput &sol = solver->solve(HQPData);
429 
430  BOOST_CHECK_MESSAGE(sol.status == HQP_STATUS_OPTIMAL,
431  "Status " + toString(sol.status));
432 
433  for (ConstraintLevel::const_iterator it = HQPData[0].begin();
434  it != HQPData[0].end(); it++) {
435  auto constr = it->second;
436  if (constr->checkConstraint(sol.x) == false) {
437  if (constr->isEquality()) {
438  BOOST_CHECK_MESSAGE(
439  false,
440  "Equality " + constr->name() + " violated: " +
441  toString(
442  (constr->matrix() * sol.x - constr->vector()).norm()));
443  } else if (constr->isInequality()) {
444  BOOST_CHECK_MESSAGE(
445  false,
446  "Inequality " + constr->name() + " violated: " +
447  toString((constr->matrix() * sol.x - constr->lowerBound())
448  .minCoeff()) +
449  "\n" +
450  toString((constr->upperBound() - constr->matrix() * sol.x)
451  .minCoeff()));
452  } else if (constr->isBound()) {
453  BOOST_CHECK_MESSAGE(
454  false, "Bound " + constr->name() + " violated: " +
455  toString((sol.x - constr->lowerBound()).minCoeff()) +
456  "\n" +
457  toString((constr->upperBound() - sol.x).minCoeff()));
458  }
459  }
460  }
461 
462  dv = sol.x.head(nv);
463  f_RF = sol.x.segment<12>(nv);
464  f_LF = sol.x.segment<12>(nv + 12);
465  f = sol.x.tail(24);
466 
467  BOOST_CHECK(contactRF.getMotionConstraint().checkConstraint(dv));
468  BOOST_CHECK(contactRF.getForceConstraint().checkConstraint(f_RF));
469  BOOST_CHECK(contactLF.getMotionConstraint().checkConstraint(dv));
470  BOOST_CHECK(contactLF.getForceConstraint().checkConstraint(f_LF));
471 
472  // unsigned int index = 0;
473  // for(vector<ContactBase*>::iterator it=contacts.begin();
474  // it!=contacts.end(); it++)
475  // {
476  // unsigned int m = (*it)->n_force();
477  // const Matrix & T = (*it)->getForceGeneratorMatrix(); // 6x12
478  // Jc.middleRows(index, m) =
479  // T.transpose()*(*it)->getMotionConstraint().matrix(); index += m;
480  // }
481  // const Matrix & M_u = robot.mass(data).topRows<6>();
482  // const Vector & h_u = robot.nonLinearEffects(data).head<6>();
483  // const Matrix & J_u = Jc.leftCols<6>();
484  // CHECK_LESS_THAN((M_u*dv + h_u - J_u.transpose()*f).norm(), 1e-6);
485 
486  v += dt * dv;
487  q = pinocchio::integrate(robot.model(), q, dt * v);
488  t += dt;
489 
490  REQUIRE_FINITE(dv.transpose());
491  REQUIRE_FINITE(v.transpose());
492  REQUIRE_FINITE(q.transpose());
493  CHECK_LESS_THAN(dv.norm(), 1e6);
494  CHECK_LESS_THAN(v.norm(), 1e6);
495  }
496 
497  delete solver;
498  cout << "\n### TEST FINISHED ###\n";
499  PRINT_VECTOR(v);
500  cout << "Final CoM position: " << robot.com(tsid->data()).transpose()
501  << endl;
502  cout << "Desired CoM position: " << com_ref.transpose() << endl;
503 }
504 
505 BOOST_AUTO_TEST_CASE(test_contact_point_invdyn_formulation_acc_force) {
506  cout << "\n*** test_contact_point_invdyn_formulation_acc_force ***\n";
507 
508  const double mu = 0.3;
509  const double fMin = 0.0;
510  const double fMax = 10.0;
511  const std::string frameName = "base_link";
512  const double dt = 1e-3;
513 
514  double t = 0.;
515 
516  double w_com = 1.0; // weight of center of mass task
517  double w_forceReg = 1e-5; // weight of force regularization task
518  double kp_contact = 100.0; // proportional gain of contact constraint
519  double kp_com = 1.0; // proportional gain of center of mass task
520 
521  vector<string> package_dirs;
523  string urdfFileName = package_dirs[0] + "/urdf/quadruped.urdf";
524  RobotWrapper robot(urdfFileName, package_dirs,
526 
527  BOOST_REQUIRE(robot.model().existFrame(frameName));
528 
529  Vector q = neutral(robot.model());
530  Vector v = Vector::Zero(robot.nv());
531  const unsigned int nv = robot.nv();
532 
533  // Create initial posture.
534  q(0) = 0.1;
535  q(2) = 0.5;
536  q(6) = 1.;
537  for (int i = 0; i < 4; i++) {
538  q(7 + 2 * i) = -0.4;
539  q(8 + 2 * i) = 0.8;
540  }
541 
542  // Create the inverse-dynamics formulation
543  auto tsid =
544  std::make_shared<InverseDynamicsFormulationAccForce>("tsid", robot);
545  tsid->computeProblemData(t, q, v);
546  pinocchio::Data &data = tsid->data();
547 
548  // Place the robot onto the ground.
549 
550  pinocchio::SE3 fl_contact =
551  robot.framePosition(data, robot.model().getFrameId("FL_contact"));
552  q[2] -= fl_contact.translation()(2);
553 
554  tsid->computeProblemData(t, q, v);
555 
556  // Add task for the COM.
557  auto comTask = std::make_shared<TaskComEquality>("task-com", robot);
558  comTask->Kp(kp_com * Vector::Ones(3));
559  comTask->Kd(2.0 * comTask->Kp().cwiseSqrt());
560  tsid->addMotionTask(*comTask, w_com, 1);
561 
562  Vector3 com_ref = robot.com(data);
563  auto trajCom =
564  std::make_shared<TrajectoryEuclidianConstant>("traj_com", com_ref);
566  sampleCom = trajCom->computeNext();
567  comTask->setReference(sampleCom);
568 
569  // Add contact constraints.
570  std::string contactFrames[] = {"BL_contact", "BR_contact", "FL_contact",
571  "FR_contact"};
572 
573  Vector3 contactNormal = Vector3::UnitZ();
574  std::vector<std::shared_ptr<ContactPoint>> contacts(4);
575 
576  for (int i = 0; i < 4; i++) {
577  auto cp = std::make_shared<ContactPoint>("contact_" + contactFrames[i],
578  robot, contactFrames[i],
580  cp->Kp(kp_contact * Vector::Ones(3));
581  cp->Kd(2.0 * sqrt(kp_contact) * Vector::Ones(3));
582  cp->setReference(
583  robot.framePosition(data, robot.model().getFrameId(contactFrames[i])));
584  cp->useLocalFrame(false);
585  tsid->addRigidContact(*cp, w_forceReg, 1.0, 1);
586 
587  contacts[i] = cp;
588  }
589 
590  // Create an HQP solver
591  SolverHQPBase *solver = SolverHQPFactory::createNewSolver(
592  SOLVER_HQP_EIQUADPROG, "solver-eiquadprog");
593  solver->resize(tsid->nVar(), tsid->nEq(), tsid->nIn());
594 
595  Vector dv = Vector::Zero(nv);
596  const HQPOutput *sol;
597  for (int i = 0; i < max_it; i++) {
598  const HQPData &HQPData = tsid->computeProblemData(t, q, v);
599 
601 
602  for (unsigned int i = 0; i < contacts.size(); i++) {
604  }
605 
606  sol = &(solver->solve(HQPData));
607 
608  BOOST_CHECK_MESSAGE(sol->status == HQP_STATUS_OPTIMAL,
609  "Status " + toString(sol->status));
610 
611  for (ConstraintLevel::const_iterator it = HQPData[0].begin();
612  it != HQPData[0].end(); it++) {
613  auto constr = it->second;
614  if (constr->checkConstraint(sol->x) == false) {
615  if (constr->isEquality()) {
616  BOOST_CHECK_MESSAGE(
617  false,
618  "Equality " + constr->name() + " violated: " +
619  toString(
620  (constr->matrix() * sol->x - constr->vector()).norm()));
621  } else if (constr->isInequality()) {
622  BOOST_CHECK_MESSAGE(
623  false,
624  "Inequality " + constr->name() + " violated: " +
625  toString((constr->matrix() * sol->x - constr->lowerBound())
626  .minCoeff()) +
627  "\n" +
628  toString((constr->upperBound() - constr->matrix() * sol->x)
629  .minCoeff()));
630  } else if (constr->isBound()) {
631  BOOST_CHECK_MESSAGE(
632  false, "Bound " + constr->name() + " violated: " +
633  toString((sol->x - constr->lowerBound()).minCoeff()) +
634  "\n" +
635  toString((constr->upperBound() - sol->x).minCoeff()));
636  }
637  }
638  }
639 
640  dv = sol->x.head(nv);
641 
642  v += dt * dv;
643  q = pinocchio::integrate(robot.model(), q, dt * v);
644  t += dt;
645 
646  REQUIRE_FINITE(dv.transpose());
647  REQUIRE_FINITE(v.transpose());
648  REQUIRE_FINITE(q.transpose());
649  CHECK_LESS_THAN(dv.norm(), 1e6);
650  CHECK_LESS_THAN(v.norm(), 1e6);
651  }
652 
653  for (int i = 0; i < 4; i++) {
654  Eigen::Matrix<double, 3, 1> f;
655  tsid->getContactForces(contacts[i]->name(), *sol, f);
656  cout << contacts[i]->name() << " force:" << f.transpose() << endl;
657  }
658 
659  delete solver;
660 
661  cout << "\n### TEST FINISHED ###\n";
662  PRINT_VECTOR(v);
663  cout << "Final CoM position: " << robot.com(tsid->data()).transpose()
664  << endl;
665  cout << "Desired CoM position: " << com_ref.transpose() << endl;
666 }
667 
668 #define PROFILE_CONTROL_CYCLE "Control cycle"
669 #define PROFILE_PROBLEM_FORMULATION "Problem formulation"
670 #define PROFILE_HQP "HQP"
671 #define PROFILE_HQP_FAST "HQP_FAST"
672 #define PROFILE_HQP_RT "HQP_RT"
673 
674 BOOST_AUTO_TEST_CASE(test_invdyn_formulation_acc_force_computation_time) {
675  cout << "\n*** test_invdyn_formulation_acc_force_computation_time ***\n";
676 
677  const double dt = 0.001;
678  double t = 0.0;
679 
680  StandardRomeoInvDynCtrl romeo_inv_dyn(dt);
681  RobotWrapper &robot = *(romeo_inv_dyn.robot);
682  auto tsid = romeo_inv_dyn.tsid;
683  TaskComEquality &comTask = *(romeo_inv_dyn.comTask);
684  TaskJointPosture &postureTask = *(romeo_inv_dyn.postureTask);
685  Vector q = romeo_inv_dyn.q;
686  Vector v = romeo_inv_dyn.v;
687  const int nv = robot.model().nv;
688 
689  Vector3 com_ref = robot.com(tsid->data());
690  com_ref(1) += 0.1;
691  auto trajCom =
692  std::make_shared<TrajectoryEuclidianConstant>("traj_com", com_ref);
694 
695  Vector q_ref = q.tail(nv - 6);
696  auto trajPosture =
697  std::make_shared<TrajectoryEuclidianConstant>("traj_posture", q_ref);
699 
700  // Create an HQP solver
702  SolverHQPFactory::createNewSolver(SOLVER_HQP_EIQUADPROG, "eiquadprog");
703  SolverHQPBase *solver_fast = SolverHQPFactory::createNewSolver(
704  SOLVER_HQP_EIQUADPROG_FAST, "eiquadprog-fast");
705  SolverHQPBase *solver_rt = SolverHQPFactory::createNewSolver<61, 18, 71>(
706  SOLVER_HQP_EIQUADPROG_RT, "eiquadprog-rt");
707 
708  solver->resize(tsid->nVar(), tsid->nEq(), tsid->nIn());
709  solver_fast->resize(tsid->nVar(), tsid->nEq(), tsid->nIn());
710 
711  Vector dv = Vector::Zero(nv);
712  for (int i = 0; i < max_it; i++) {
714 
715  sampleCom = trajCom->computeNext();
716  comTask.setReference(sampleCom);
717  samplePosture = trajPosture->computeNext();
718  postureTask.setReference(samplePosture);
719 
721  const HQPData &HQPData = tsid->computeProblemData(t, q, v);
723 
725  const HQPOutput &sol = solver->solve(HQPData);
727 
729 
731  const HQPOutput &sol_fast = solver_fast->solve(HQPData);
733 
735  solver_rt->solve(HQPData);
737 
738  getStatistics().store("active inequalities",
739  static_cast<double>(sol_fast.activeSet.size()));
740  getStatistics().store("solver iterations", sol_fast.iterations);
741 
742  dv = sol.x.head(nv);
743  v += dt * dv;
744  q = pinocchio::integrate(robot.model(), q, dt * v);
745  t += dt;
746 
747  REQUIRE_FINITE(dv.transpose());
748  REQUIRE_FINITE(v.transpose());
749  REQUIRE_FINITE(q.transpose());
750  }
751  delete solver;
752  delete solver_fast;
753  delete solver_rt;
754  cout << "\n### TEST FINISHED ###\n";
755  getProfiler().report_all(3, cout);
756  getStatistics().report_all(1, cout);
757 }
758 
759 BOOST_AUTO_TEST_SUITE_END()
demo_quadruped.kp_com
float kp_com
Definition: demo_quadruped.py:38
PROFILE_HQP_RT
#define PROFILE_HQP_RT
Definition: tsid-formulation.cpp:672
StandardRomeoInvDynCtrl::H_lf_ref
pinocchio::SE3 H_lf_ref
Definition: tsid-formulation.cpp:108
demo_quadruped.v
v
Definition: demo_quadruped.py:80
Stopwatch::stop
void stop(std::string perf_name)
Definition: stop-watch.cpp:120
sol
sol
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_invdyn_formulation_acc_force_remove_contact)
Definition: tsid-formulation.cpp:197
REQUIRE_CONTACT_FINITE
#define REQUIRE_CONTACT_FINITE(contact)
Definition: tsid-formulation.cpp:57
ex_4_conf.lf_frame_name
string lf_frame_name
Definition: ex_4_conf.py:34
StandardRomeoInvDynCtrl::lyp
static const double lyp
Definition: tsid-formulation.cpp:81
demo_quadruped.fMax
float fMax
Definition: demo_quadruped.py:27
tsid::solvers::HQPOutput::activeSet
VectorXi activeSet
Lagrange multipliers.
Definition: solver-HQP-output.hpp:39
StandardRomeoInvDynCtrl::tsid
std::shared_ptr< InverseDynamicsFormulationAccForce > tsid
Definition: tsid-formulation.cpp:99
tsid::trajectories::TrajectorySample
Definition: trajectories/trajectory-base.hpp:33
pinocchio::DataTpl
StandardRomeoInvDynCtrl::kp_contact
static const double kp_contact
Definition: tsid-formulation.cpp:93
quadruped_model_path
const string quadruped_model_path
Definition: tsid-formulation.cpp:67
demo_quadruped.sampleCom
sampleCom
Definition: demo_quadruped.py:120
test_Formulation.H_lf_ref
H_lf_ref
Definition: test_Formulation.py:87
tsid::solvers::SolverHQPBase::solve
virtual const HQPOutput & solve(const HQPData &problemData)=0
dv
dv
ex_4_walking.f_RF
f_RF
Definition: ex_4_walking.py:81
ex_4_conf.lyp
float lyp
Definition: ex_4_conf.py:27
ex_4_conf.lz
float lz
Definition: ex_4_conf.py:29
contact-point.hpp
test_Formulation.REMOVE_CONTACT_N
int REMOVE_CONTACT_N
Definition: test_Formulation.py:104
CHECK_LESS_THAN
#define CHECK_LESS_THAN(A, B)
Definition: tsid-formulation.cpp:50
StandardRomeoInvDynCtrl::jointBoundsTask
std::shared_ptr< TaskJointBounds > jointBoundsTask
Definition: tsid-formulation.cpp:104
tsid::trajectories
Definition: trajectories/fwd.hpp:22
StandardRomeoInvDynCtrl::lxn
static const double lxn
Definition: tsid-formulation.cpp:80
tsid::tasks::TaskJointPosture
Definition: tasks/task-joint-posture.hpp:29
test_Formulation.w_RF
int w_RF
Definition: test_Formulation.py:107
StandardRomeoInvDynCtrl::comTask
std::shared_ptr< TaskComEquality > comTask
Definition: tsid-formulation.cpp:102
test_Formulation.contactRF
contactRF
Definition: test_Formulation.py:57
pinocchio::SE3
context::SE3 SE3
ex_4_conf.rf_frame_name
string rf_frame_name
Definition: ex_4_conf.py:33
i
int i
test_Formulation.CONTACT_TRANSITION_TIME
float CONTACT_TRANSITION_TIME
Definition: test_Formulation.py:105
task-joint-bounds.hpp
test_Formulation.tau_old
tau_old
Definition: test_Formulation.py:135
setup.data
data
Definition: setup.in.py:48
tsid::robots
Definition: robots/fwd.hpp:22
test_Formulation.rightFootTask
rightFootTask
Definition: test_Formulation.py:109
task-com-equality.hpp
demo_quadruped.robot
robot
Definition: demo_quadruped.py:51
utils.hpp
StandardRomeoInvDynCtrl::lf_frame_name
static const std::string lf_frame_name
Definition: tsid-formulation.cpp:88
tsid::math::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
demo_quadruped.comTask
comTask
Definition: demo_quadruped.py:108
demo_quadruped.w_posture
int w_posture
Definition: demo_quadruped.py:34
tsid::math::vectorToSE3
void vectorToSE3(RefVector vec, pinocchio::SE3 &M)
Definition: src/math/utils.cpp:38
demo_quadruped.H_rf_ref
H_rf_ref
Definition: demo_quadruped.py:103
pinocchio::JointModelFreeFlyerTpl
StandardRomeoInvDynCtrl::kp_com
static const double kp_com
Definition: tsid-formulation.cpp:94
StandardRomeoInvDynCtrl
Definition: tsid-formulation.cpp:77
f
f
tsid::solvers::SolverHQPBase::resize
virtual void resize(unsigned int n, unsigned int neq, unsigned int nin)=0
StandardRomeoInvDynCtrl::contactRF
std::shared_ptr< Contact6d > contactRF
Definition: tsid-formulation.cpp:100
tsid::math
Definition: constraint-base.hpp:26
PROFILE_HQP
#define PROFILE_HQP
Definition: tsid-formulation.cpp:670
demo_quadruped.samplePosture
samplePosture
Definition: demo_quadruped.py:162
tsid::contacts
Definition: contacts/contact-6d.hpp:28
demo_quadruped.q
q
Definition: demo_quadruped.py:74
ex_4_conf.nv
int nv
Definition: ex_4_conf.py:23
StandardRomeoInvDynCtrl::rf_frame_name
static const std::string rf_frame_name
Definition: tsid-formulation.cpp:87
getProfiler
Stopwatch & getProfiler()
Definition: stop-watch.cpp:43
StandardRomeoInvDynCtrl::robot
std::shared_ptr< RobotWrapper > robot
Definition: tsid-formulation.cpp:98
StandardRomeoInvDynCtrl::w_forceReg
static const double w_forceReg
Definition: tsid-formulation.cpp:92
REQUIRE_FINITE
#define REQUIRE_FINITE(A)
Definition: tsid-formulation.cpp:49
StandardRomeoInvDynCtrl::v
Vector v
Definition: tsid-formulation.cpp:106
task-joint-posture.hpp
tsid::contacts::Contact6d
Definition: contacts/contact-6d.hpp:29
demo_quadruped.kp_contact
float kp_contact
Definition: demo_quadruped.py:37
tsid::solvers::HQPOutput
Definition: solver-HQP-output.hpp:29
Statistics::store
void store(std::string name, const double &value)
Definition: statistics.cpp:40
demo_quadruped.tau
tau
Definition: demo_quadruped.py:174
demo_quadruped.PRINT_N
int PRINT_N
Definition: demo_quadruped.py:42
package_dirs
package_dirs
utils.hpp
StandardRomeoInvDynCtrl::mu
static const double mu
Definition: tsid-formulation.cpp:84
demo_quadruped.postureTask
postureTask
Definition: demo_quadruped.py:113
demo_quadruped.trajPosture
trajPosture
Definition: demo_quadruped.py:123
tsid::tasks::TaskComEquality
Definition: tasks/task-com-equality.hpp:29
tsid::solvers::SolverHQPBase
Abstract interface for a Quadratic Program (HQP) solver.
Definition: solver-HQP-base.hpp:34
StandardRomeoInvDynCtrl::w_posture
static const double w_posture
Definition: tsid-formulation.cpp:91
StandardRomeoInvDynCtrl::w_com
static const double w_com
Definition: tsid-formulation.cpp:90
demo_quadruped.dt
float dt
Definition: demo_quadruped.py:41
pinocchio::integrate
void integrate(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout)
SOLVER_HQP_EIQUADPROG
SOLVER_HQP_EIQUADPROG
Definition: solvers/fwd.hpp:37
tsid::solvers::HQPDataToString
std::string HQPDataToString(const HQPData &data, bool printMatrices=false)
Definition: src/solvers/utils.cpp:26
tsid::math::Matrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Definition: math/fwd.hpp:36
StandardRomeoInvDynCtrl::contactNormal
static const Vector3 contactNormal
Definition: tsid-formulation.cpp:89
PROFILE_HQP_FAST
#define PROFILE_HQP_FAST
Definition: tsid-formulation.cpp:671
PRINT_VECTOR
#define PRINT_VECTOR(a)
Definition: math/utils.hpp:30
max_it
const int max_it
Definition: tsid-formulation.cpp:70
task-se3-equality.hpp
inverse-dynamics-formulation-acc-force.hpp
demo_quadruped.contacts
int contacts
Definition: demo_quadruped.py:98
romeo_model_path
const string romeo_model_path
Definition: tsid-formulation.cpp:66
ex_4_conf.lxp
float lxp
Definition: ex_4_conf.py:25
setup.name
name
Definition: setup.in.py:179
ex_4_conf.lyn
float lyn
Definition: ex_4_conf.py:28
stop-watch.hpp
statistics.hpp
HQP_STATUS_OPTIMAL
HQP_STATUS_OPTIMAL
Definition: solvers/fwd.hpp:63
it
int it
demo_quadruped.mu
float mu
Definition: demo_quadruped.py:25
ex_4_walking.f_LF
f_LF
Definition: ex_4_walking.py:82
StandardRomeoInvDynCtrl::contactLF
std::shared_ptr< Contact6d > contactLF
Definition: tsid-formulation.cpp:101
tsid::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
cp
cp
tsid::tasks
Definition: contacts/fwd.hpp:22
StandardRomeoInvDynCtrl::kp_posture
static const double kp_posture
Definition: tsid-formulation.cpp:95
joint-configuration.hpp
PROFILE_PROBLEM_FORMULATION
#define PROFILE_PROBLEM_FORMULATION
Definition: tsid-formulation.cpp:669
demo_quadruped.kp_posture
float kp_posture
Definition: demo_quadruped.py:39
Statistics::report_all
void report_all(int precision=2, std::ostream &output=std::cout)
Definition: statistics.cpp:71
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
tsid::solvers
Definition: solvers/fwd.hpp:31
StandardRomeoInvDynCtrl::fMin
static const double fMin
Definition: tsid-formulation.cpp:85
contact-6d.hpp
std
StandardRomeoInvDynCtrl::lz
static const double lz
Definition: tsid-formulation.cpp:83
demo_quadruped.trajCom
trajCom
Definition: demo_quadruped.py:119
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
pinocchio::srdf::loadReferenceConfigurations
void loadReferenceConfigurations(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const bool verbose=false)
StandardRomeoInvDynCtrl::q
Vector q
Definition: tsid-formulation.cpp:105
StandardRomeoInvDynCtrl::H_rf_ref
pinocchio::SE3 H_rf_ref
Definition: tsid-formulation.cpp:107
test_Formulation.kp_RF
float kp_RF
Definition: test_Formulation.py:106
demo_quadruped.fMin
float fMin
Definition: demo_quadruped.py:26
demo_quadruped.com_ref
com_ref
Definition: demo_quadruped.py:118
StandardRomeoInvDynCtrl::lxp
static const double lxp
Definition: tsid-formulation.cpp:79
demo_quadruped.q_ref
q_ref
Definition: demo_quadruped.py:122
neutral
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
t
Transform3f t
test_Contact.frameName
string frameName
Definition: test_Contact.py:29
PROFILE_CONTROL_CYCLE
#define PROFILE_CONTROL_CYCLE
Definition: tsid-formulation.cpp:668
StandardRomeoInvDynCtrl::lyn
static const double lyn
Definition: tsid-formulation.cpp:82
demo_quadruped.contactNormal
contactNormal
Definition: demo_quadruped.py:29
demo_quadruped.w_com
float w_com
Definition: demo_quadruped.py:33
demo_quadruped.solver
solver
Definition: demo_quadruped.py:134
tsid::solvers::HQPData
pinocchio::container::aligned_vector< ConstraintLevel > HQPData
Definition: solvers/fwd.hpp:99
tsid::toString
std::string toString(const T &v)
Definition: math/utils.hpp:39
SOLVER_HQP_EIQUADPROG_FAST
SOLVER_HQP_EIQUADPROG_FAST
Definition: solvers/fwd.hpp:38
tsid::math::Vector3
Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: math/fwd.hpp:40
Stopwatch::start
void start(std::string perf_name)
Definition: stop-watch.cpp:102
StandardRomeoInvDynCtrl::t
double t
Definition: tsid-formulation.cpp:96
tsid::solvers::HQPOutput::iterations
int iterations
indexes of active inequalities
Definition: solver-HQP-output.hpp:40
trajectory-euclidian.hpp
REQUIRE_TASK_FINITE
#define REQUIRE_TASK_FINITE(task)
Definition: tsid-formulation.cpp:53
StandardRomeoInvDynCtrl::postureTask
std::shared_ptr< TaskJointPosture > postureTask
Definition: tsid-formulation.cpp:103
getStatistics
Statistics & getStatistics()
Definition: statistics.cpp:25
ex_4_conf.lxn
float lxn
Definition: ex_4_conf.py:26
Stopwatch::report_all
void report_all(int precision=2, std::ostream &output=std::cout)
Definition: stop-watch.cpp:182
StandardRomeoInvDynCtrl::StandardRomeoInvDynCtrl
StandardRomeoInvDynCtrl(double dt)
Definition: tsid-formulation.cpp:110
StandardRomeoInvDynCtrl::fMax
static const double fMax
Definition: tsid-formulation.cpp:86
test_Formulation.contactLF
contactLF
Definition: test_Formulation.py:74


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:16