GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: src/dyna_com.cpp Lines: 0 169 0.0 %
Date: 2022-12-19 14:14:12 Branches: 0 394 0.0 %

Line Branch Exec Source
1
/**
2
 * @file
3
 * @copyright Copyright (c) 2022, LAAS-CNRS, Toward, PalRobotics
4
 * @brief
5
 */
6
7
#include "dynacom/dyna_com.hpp"
8
9
#include <algorithm>
10
#include <cctype>
11
#include <eiquadprog/eiquadprog.hpp>
12
#include <example-robot-data/path.hpp>
13
#include <pinocchio/algorithm/center-of-mass.hpp>
14
#include <pinocchio/algorithm/centroidal.hpp>
15
#include <pinocchio/algorithm/frames.hpp>
16
#include <pinocchio/parsers/urdf.hpp>
17
18
#include "dynacom/contact6d.hpp"
19
20
namespace dynacom {
21
22
DynaCoM::DynaCoM() {}
23
DynaCoM::DynaCoM(const DynaCoMSettings settings) { initialize(settings); }
24
25
void DynaCoM::initialize(const DynaCoMSettings settings) {
26
  // Copy the settings internally.
27
  settings_ = settings;
28
29
  // Check if the urdf and the srdf file exists or not.
30
  bool urdf_file_exists = false;
31
  {
32
    std::ifstream f(settings_.urdf.c_str());
33
    urdf_file_exists = f.good();
34
  }
35
36
  // Build the robot model.
37
  if (urdf_file_exists) {
38
    pinocchio::urdf::buildModel(settings_.urdf,
39
                                pinocchio::JointModelFreeFlyer(), model_);
40
  } else if (settings_.urdf != "") {
41
    pinocchio::urdf::buildModelFromXML(
42
        settings_.urdf, pinocchio::JointModelFreeFlyer(), model_);
43
  } else {
44
    throw std::runtime_error("DynaCoM::DynaCoM(): settings_.urdf is empty");
45
  }
46
  // Build pinocchio cache.
47
  data_ = pinocchio::Data(model_);
48
49
  mass_ = 0.0;
50
  for (size_t k = 0; k < model_.inertias.size(); ++k) {
51
    mass_ += model_.inertias[k].mass();
52
  }
53
  weight_ = mass_ * model_.gravity981;
54
  S_ << 0, -1, 1, 0;
55
  Sz_.setZero();
56
  Sz_.diagonal().segment<4>(2) << 1, 1, 1, 1;
57
58
  // matrix_sizes
59
  uni_rows_ = 0;
60
  fri_rows_ = 0;
61
  cols_ = 0;
62
  newton_euler_b_.resize(6);
63
}
64
65
const Eigen::Matrix<double, 6, 6> DynaCoM::toWorldCoPWrench(
66
    pinocchio::SE3 pose) {
67
  /**
68
   * To compute any CoP, we need some surface. We compute the full
69
   * robot CoP considering always a horizontal surface. So, just
70
   * the vertical forces produce pressure on such surface.
71
   * This method generates the adjoint matrix needed to transform
72
   * local forces in some frame pose to a world wrench composed by
73
   * the vertical force and the torque. Lateral forces are discarted
74
   * because they do not contribute on this CoP.
75
   * Still, notice that the lateral forces have an effect that is
76
   * accounted in the non-linear effects.
77
   */
78
79
  soMs_ = pinocchio::SE3(pose.rotation(), Eigen::Vector3d::Zero());
80
  soXs_ = soMs_.toActionMatrixInverse().transpose();
81
  oMso_ = pinocchio::SE3(Eigen::Matrix3d::Identity(), pose.translation());
82
  oXso_ = oMso_.toActionMatrixInverse().transpose();
83
84
  return oXso_ * Sz_ * soXs_;
85
}
86
87
void DynaCoM::computeDynamics(const Eigen::VectorXd &posture,
88
                              const Eigen::VectorXd &velocity,
89
                              const Eigen::VectorXd &acceleration,
90
                              const Eigen::Matrix<double, 6, 1> &externalWrench,
91
                              bool flatHorizontalGround) {
92
  /**
93
   * @brief The external wrench is supposed to be expressed
94
   * in the frame of the Center of mass.
95
   *
96
   * @brief The option flatHorizontalGround assumes that supporting contacts
97
   * where previously defined.
98
   *
99
   * TODO: In the case when flatHorizontalGround = True, still, we could
100
   * remove the assumption of horizontal ground by including the lateral force
101
   * produced by the lateral components of the groundNormalReaction.
102
   *
103
   * For this we should know what is the direction normal to the ground. Then,
104
   * we could change the flag name by `bool flatGround`. The normal direction
105
   * can be obtained from the feet frames (both are the same in a flatGround)
106
   *
107
   */
108
109
  pinocchio::computeCentroidalMomentumTimeVariation(model_, data_, posture,
110
                                                    velocity, acceleration);
111
112
  acom_ = data_.dhg.linear() / mass_;
113
  dL_ = data_.dhg.angular();
114
  L_ = data_.hg.angular();
115
116
  groundCoMForce_ = data_.dhg.linear() - weight_ - externalWrench.head<3>();
117
  groundCoMTorque_ = dL_ - externalWrench.tail<3>();
118
119
  if (flatHorizontalGround)
120
    cop_ =
121
        data_.com[0].head<2>() + (S_ * groundCoMTorque_.head<2>() -
122
                                  groundCoMForce_.head<2>() * data_.com[0](2)) /
123
                                     (groundCoMForce_(2));
124
125
  else {
126
    distributeForce(groundCoMForce_, groundCoMTorque_, data_.com[0]);
127
    // @TODO: IT could happen that the expected groundCoMwrench is not feasible,
128
    // in such case, we should get the clossest possible and recompute the
129
    // centroidal motion accordingly. So, groundCoMForce_(2) in the following
130
    // should be updated.
131
    // The case when no contact is active should also be managed.
132
133
    CoPTorque_ = Eigen::Vector3d::Zero();
134
    for (std::string name : active_contact6ds_) {
135
      std::shared_ptr<Contact6D> &contact = known_contact6ds_[name];
136
      CoPTorque_ +=
137
          (toWorldCoPWrench(contact->getPose()) * contact->appliedForce())
138
              .segment<3>(3);
139
    }
140
    cop_ = S_ * CoPTorque_.head<2>() / groundCoMForce_(2);
141
  }
142
}
143
144
void DynaCoM::computeNL(const double &w, const Eigen::VectorXd &posture,
145
                        const Eigen::VectorXd &velocity,
146
                        const Eigen::VectorXd &acceleration,
147
                        const Eigen::Matrix<double, 6, 1> &externalWrench,
148
                        bool flatHorizontalGround) {
149
  computeDynamics(posture, velocity, acceleration, externalWrench,
150
                  flatHorizontalGround);
151
  computeNL(w);
152
}
153
154
void DynaCoM::computeNL(const double &w) {
155
  /**
156
   * In this function form, computeDynamics is supposed to have been called
157
   * before.
158
   */
159
  n_ = acom_.head<2>() / (w * w) - data_.com[0].head<2>() + cop_;
160
}
161
162
// Contact management
163
// //////////////////////////////////////////////////////////////////
164
165
void DynaCoM::addContact6d(const std::shared_ptr<Contact6D> &contact,
166
                           const std::string &name, const bool active) {
167
  contact->setFrameID(model_.getFrameId(contact->getSettings().frame_name));
168
  contact->setPose(data_.oMf[contact->getFrameID()]);
169
170
  known_contact6ds_.insert(
171
      std::pair<std::string, std::shared_ptr<Contact6D>>(name, contact));
172
173
  addSizes(known_contact6ds_[name]);
174
  if (active) activateContact6d(name);
175
}
176
177
void DynaCoM::removeContact6d(const std::string &name) {
178
  knownID_ = known_contact6ds_.find(name);
179
  if (knownID_ != known_contact6ds_.end()) {
180
    removeSizes(known_contact6ds_[name]);
181
    deactivateContact6d(name);
182
    known_contact6ds_.erase(name);
183
  }
184
}
185
186
void DynaCoM::addSizes(const std::shared_ptr<Contact6D> &contact) {
187
  uni_rows_ += contact->uni_rows();
188
  fri_rows_ += contact->fri_rows();
189
  cols_ += contact->cols();
190
191
  resizeMatrices();
192
}
193
194
void DynaCoM::removeSizes(const std::shared_ptr<Contact6D> &contact) {
195
  uni_rows_ -= contact->uni_rows();
196
  fri_rows_ -= contact->fri_rows();
197
  cols_ -= contact->cols();
198
199
  resizeMatrices();
200
}
201
202
void DynaCoM::resizeMatrices() {
203
  unilaterality_A_.resize(uni_rows_, cols_);
204
  unilaterality_b_.resize(uni_rows_);
205
  friction_A_.resize(fri_rows_, cols_);
206
  friction_b_.resize(fri_rows_);
207
  regularization_A_.resize(cols_);
208
  regularization_b_.resize(cols_);
209
  newton_euler_A_.resize(6, cols_);
210
}
211
212
void DynaCoM::activateContact6d(const std::string &name) {
213
  activeID_ =
214
      std::find(active_contact6ds_.begin(), active_contact6ds_.end(), name);
215
  knownID_ = known_contact6ds_.find(name);
216
217
  if (activeID_ == active_contact6ds_.end()) {
218
    if (knownID_ != known_contact6ds_.end()) {
219
      active_contact6ds_.push_back(name);
220
      std::cout << "activated contact " << name << std::endl;
221
      return;
222
    } else {
223
      std::cout << "no contact called " << name << " was defined" << std::endl;
224
      return;
225
    }
226
  }
227
  std::cout << name << " was already active" << std::endl;
228
}
229
230
void DynaCoM::deactivateContact6d(const std::string &name) {
231
  activeID_ =
232
      std::find(active_contact6ds_.begin(), active_contact6ds_.end(), name);
233
  if (activeID_ != active_contact6ds_.end()) {
234
    known_contact6ds_[name]->deactivate();
235
    active_contact6ds_.erase(activeID_);
236
    std::cout << "deactivated contact " << name << std::endl;
237
    return;
238
  }
239
  std::cout << name << " was not active" << std::endl;
240
}
241
242
void DynaCoM::buildMatrices(const Eigen::Vector3d &groundCoMForce,
243
                            const Eigen::Vector3d &groundCoMTorque,
244
                            const Eigen::Vector3d &CoM) {
245
  size_t uni_r, fri_r, cols;
246
247
  uni_i_ = 0;
248
  fri_i_ = 0;
249
  j_ = 0;
250
  for (std::string name : active_contact6ds_) {
251
    std::shared_ptr<Contact6D> &contact = known_contact6ds_[name];
252
253
    uni_r = contact->uni_rows();
254
    fri_r = contact->fri_rows();
255
    cols = contact->cols();
256
257
    unilaterality_A_.block(uni_i_, j_, uni_r, cols) << contact->uni_A();
258
    unilaterality_A_.block(0, j_, uni_i_, cols).setZero();
259
    unilaterality_A_.block(uni_i_, 0, uni_r, j_).setZero();
260
    unilaterality_b_.segment(uni_i_, uni_r) << contact->uni_b();
261
262
    friction_A_.block(fri_i_, j_, fri_r, cols) << contact->fri_A();
263
    friction_A_.block(0, j_, fri_i_, cols).setZero();
264
    friction_A_.block(fri_i_, 0, fri_r, j_).setZero();
265
    friction_b_.segment(fri_i_, fri_r) << contact->fri_b();
266
267
    regularization_A_.segment(j_, cols) << contact->reg_A();
268
    regularization_b_.segment(j_, cols) << contact->reg_b();
269
270
    contact->updateNewtonEuler(CoM, pinocchio::updateFramePlacement(
271
                                        model_, data_, contact->getFrameID()));
272
    newton_euler_A_.block(0, j_, 6, cols) << contact->NE_A();
273
274
    uni_i_ += uni_r;
275
    fri_i_ += fri_r;
276
    j_ += cols;
277
  }
278
  newton_euler_b_ << groundCoMForce, groundCoMTorque;
279
}
280
281
// void DynaCoM::solveQP() {
282
//   H_.resize(j_, j_);
283
//   g_.resize(j_);
284
//   C_.resize(uni_i_ + fri_i_, j_);
285
//   u_.resize(uni_i_ + fri_i_);
286
//   l_.resize(uni_i_ + fri_i_);
287
//   A_.resize(6, j_);
288
289
//  H_.setZero();
290
//  g_.setZero();
291
//  H_.diagonal() << (regularization_A_.cwiseAbs2()).segment(0, j_);
292
//  C_ << unilaterality_A_.block(0, 0, uni_i_, j_),
293
//      friction_A_.block(0, 0, fri_i_, j_);
294
295
//  u_.setZero();
296
//  l_.setConstant(-inf_);
297
//  A_ << newton_euler_A_.block(0, 0, 6, j_);
298
//  b_ << newton_euler_b_;
299
//  // Initialization of QP solver
300
//  // std::cout << "matrix H:\n " << H_ << std::endl;
301
//  // std::cout << "matrix A:\n " << A_ << std::endl;
302
//  // std::cout << "matrix b:\n " << b_ << std::endl;
303
//  // std::cout << "matrix C:\n " << C_ << std::endl;
304
305
//  // std::cout<<"In solveQP, matrices made, starting proxQP"<<std::endl;
306
//  proxsuite::proxqp::dense::isize dim = j_;
307
//  proxsuite::proxqp::dense::isize n_eq(6);
308
//  proxsuite::proxqp::dense::isize n_in(fri_i_ + uni_i_);
309
//  proxsuite::proxqp::dense::QP<double> qp(dim, n_eq, n_in);
310
311
//  qp.init(H_, g_, A_, b_, C_, l_,
312
//          u_);  //,std::nullopt,std::nullopt,std::nullopt
313
//  qp.solve();
314
315
//  F_.resize(j_);
316
//  F_ << qp.results.x;
317
//  // Check results
318
//  // std::cout << "solution:\n " << F_ << std::endl;
319
//}
320
321
void DynaCoM::solveQP() {
322
  /* eiquadprog formulation :
323
  min 0.5 * x G x + g0 x
324
  s.t.
325
  CE^T x + ce0 = 0
326
  CI^T x + ci0 >= 0
327
  */
328
329
  /* proxsuite formulation :
330
  min 0.5 * x H x + g^T x
331
  s.t.
332
  A x = b
333
  l <= C x <= u
334
  */
335
336
  int dim(static_cast<int>(j_));  // number of variables
337
  int n_eq(6);                    // number of equality constraints
338
  int n_ineq(
339
      static_cast<int>(fri_i_ + uni_i_));  // number of inequalities constraints
340
341
  F_.resize(dim);
342
  G_.resize(dim, dim);
343
  g0_.resize(dim);
344
  CE_.resize(dim, n_eq);
345
  ce0_.resize(n_eq);
346
  C_.resize(n_ineq, dim);
347
  CI_.resize(dim, n_ineq);
348
  ci0_.resize(n_ineq);
349
350
  G_.setZero();
351
  G_.diagonal() << (regularization_A_.cwiseAbs2()).segment(0, dim);
352
  g0_.setZero();
353
354
  CE_ << newton_euler_A_.block(0, 0, 6, dim).transpose();
355
  ce0_ << -newton_euler_b_;
356
357
  C_ << unilaterality_A_.block(0, 0, static_cast<int>(uni_i_), dim),
358
      friction_A_.block(0, 0, static_cast<int>(fri_i_), dim);
359
  CI_ = -C_.transpose();
360
  ci0_.setZero();
361
362
  //  std::cout<<"G "<<std::endl<<G_<<std::endl;
363
  //  std::cout<<"g0 "<<std::endl<<g0_<<std::endl;
364
  //  std::cout<<"CE "<<std::endl<<CE_<<std::endl;
365
  //  std::cout<<"ce "<<std::endl<<ce0_<<std::endl;
366
  //  std::cout<<"CI "<<std::endl<<CI_<<std::endl;
367
  //  std::cout<<"ci "<<std::endl<<ci0_<<std::endl;
368
369
  activeSetSize_ = 0;
370
  // const double precision =
371
  eiquadprog::solvers::solve_quadprog(G_, g0_, CE_, ce0_, CI_, ci0_, F_,
372
                                      activeSet_, activeSetSize_);
373
  // std::cout<<"DynaCom::SolveQP, finished with precision =
374
  // "<<precision<<std::endl;
375
}
376
377
void DynaCoM::distribute() {
378
  Eigen::Index n, i = 0;
379
  for (auto contact_pair : known_contact6ds_) {
380
    if (std::find(active_contact6ds_.begin(), active_contact6ds_.end(),
381
                  contact_pair.first) == active_contact6ds_.end()) {
382
      // Contact not active
383
      contact_pair.second->applyForce(Eigen::Matrix<double, 6, 1>::Zero());
384
    } else {
385
      // contact is active
386
      n = static_cast<int>(contact_pair.second->cols());
387
      contact_pair.second->applyForce(F_.segment(i, n));
388
      i += n;
389
    }
390
  }
391
}
392
393
void DynaCoM::distributeForce(const Eigen::Vector3d &groundCoMForce,
394
                              const Eigen::Vector3d &groundCoMTorque,
395
                              const Eigen::Vector3d &CoM) {
396
  /**
397
   *
398
   *  Make sure that the data of the dynaCoM
399
   * class has been updated to the correct robot
400
   * posture before executing this distribution.
401
   *
402
   * //@TODO: if the list of active contacts is empty, no force or torque
403
   * can be applied. Manage such case. We change the arguments? we throw
404
   * error? Check.
405
   *
406
   * */
407
408
  buildMatrices(groundCoMForce, groundCoMTorque, CoM);
409
  // std::cout<<"it is at least building the matrices"<<std::endl;
410
  solveQP();
411
  // std::cout<<"it is actually solving the QP"<<std::endl;
412
  distribute();
413
  // std::cout<<"it even distribute the forces"<<std::endl;
414
  // std::cout << "Distributed" << std::endl;
415
}
416
417
}  // namespace dynacom