GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: src/biped_ig.cpp Lines: 0 174 0.0 %
Date: 2023-12-03 14:15:28 Branches: 0 450 0.0 %

Line Branch Exec Source
1
/**
2
 * @file
3
 * @copyright Copyright (c) 2022, LAAS-CNRS, Toward, PalRobotics
4
 * @brief
5
 */
6
7
#include "aig/biped_ig.hpp"
8
9
#include <algorithm>
10
#include <cctype>
11
12
#include "aig/contact6d.hpp"
13
#include "aig/dyna_com.hpp"
14
#include "pinocchio/algorithm/center-of-mass.hpp"
15
#include "pinocchio/algorithm/centroidal.hpp"
16
#include "pinocchio/parsers/srdf.hpp"
17
#include "pinocchio/parsers/urdf.hpp"
18
19
namespace aig {
20
21
BipedIGSettings makeSettingsFor(const std::string &path_to_robots,
22
                                const std::string &robot_name) {
23
  BipedIGSettings robot_settings;
24
  std::string robot_name_lower = robot_name;
25
  std::transform(robot_name_lower.begin(), robot_name_lower.end(),
26
                 robot_name_lower.begin(),
27
                 [](unsigned char c) { return std::tolower(c); });
28
  if (robot_name_lower == "talos") {
29
    robot_settings.urdf = path_to_robots + "/robots/talos_reduced.urdf";
30
    robot_settings.srdf = path_to_robots + "/srdf/talos.srdf";
31
32
    robot_settings.left_hip_joint_name = "leg_left_1_joint";
33
    robot_settings.right_hip_joint_name = "leg_right_1_joint";
34
    robot_settings.left_knee_joint_name = "leg_left_4_joint";
35
    robot_settings.right_knee_joint_name = "leg_right_4_joint";
36
    robot_settings.left_ankle_joint_name = "leg_left_5_joint";
37
    robot_settings.right_ankle_joint_name = "leg_right_5_joint";
38
    robot_settings.left_foot_frame_name = "leg_left_sole_fix_joint";
39
    robot_settings.right_foot_frame_name = "leg_right_sole_fix_joint";
40
  } else {
41
    throw std::runtime_error(
42
        "biped_ig::aig::make_settings_for: No default settings for "
43
        "a robot with this name were specified yet.");
44
  }
45
  return robot_settings;
46
}
47
48
BipedIG::BipedIG() {
49
  // initialized by default:
50
  // model_
51
  // data_
52
  // settings_
53
  // left_leg_
54
  // right_leg_
55
  // left_arm_
56
  // right_arm_
57
}
58
59
BipedIG::BipedIG(const BipedIGSettings &settings) { initialize(settings); }
60
61
void BipedIG::initialize(const BipedIGSettings &settings) {
62
  // Copy the settings internally.
63
  settings_ = settings;
64
65
  // Check if the urdf and the srdf file exists or not.
66
  bool urdf_file_exists = false;
67
  bool srdf_file_exists = false;
68
  {
69
    std::ifstream f(settings_.urdf.c_str());
70
    urdf_file_exists = f.good();
71
  }
72
  {
73
    std::ifstream f(settings_.srdf.c_str());
74
    srdf_file_exists = f.good();
75
  }
76
77
  // Build the robot model.
78
  if (urdf_file_exists) {
79
    pinocchio::urdf::buildModel(settings_.urdf,
80
                                pinocchio::JointModelFreeFlyer(), model_);
81
  } else if (settings_.urdf != "") {
82
    pinocchio::urdf::buildModelFromXML(
83
        settings_.urdf, pinocchio::JointModelFreeFlyer(), model_);
84
  } else {
85
    throw std::runtime_error("BipedIG::BipedIG(): settings_.urdf is empty");
86
  }
87
  // Build pinocchio cache.
88
  data_ = pinocchio::Data(model_);
89
90
  // Extract the CoM to Waist level arm.
91
  if (srdf_file_exists) {
92
    pinocchio::srdf::loadReferenceConfigurations(model_, settings_.srdf, false);
93
  } else if (settings_.srdf != "") {
94
    std::stringstream buffer;
95
    buffer << settings_.srdf;
96
    pinocchio::srdf::loadReferenceConfigurationsFromXML(model_, buffer, false);
97
  } else {
98
    throw std::runtime_error("BipedIG::BipedIG(): settings_.srdf is empty");
99
  }
100
  q0_ = model_.referenceConfigurations["half_sitting"];
101
  set_com_from_waist(q0_);
102
103
  configureLegs();
104
105
  aig::DynaCoMSettings dyn_settings;
106
  dyn_settings.urdf = settings_.urdf;
107
  dynamics_ = aig::DynaCoM(dyn_settings);
108
}
109
110
void BipedIG::configureLegs() {
111
  LegIGSettings left_leg_settings, right_leg_settings;
112
  pinocchio::JointIndex left_hip_id =
113
      model_.getJointId(settings_.left_hip_joint_name);
114
  pinocchio::JointIndex left_knee_id =
115
      model_.getJointId(settings_.left_knee_joint_name);
116
  pinocchio::JointIndex left_ankle_id =
117
      model_.getJointId(settings_.left_ankle_joint_name);
118
  pinocchio::JointIndex right_hip_id =
119
      model_.getJointId(settings_.right_hip_joint_name);
120
  pinocchio::JointIndex right_knee_id =
121
      model_.getJointId(settings_.right_knee_joint_name);
122
  pinocchio::JointIndex right_ankle_id =
123
      model_.getJointId(settings_.right_ankle_joint_name);
124
  pinocchio::FrameIndex leftSoleID =
125
      model_.getFrameId(settings_.left_foot_frame_name);
126
  pinocchio::FrameIndex rightSoleID =
127
      model_.getFrameId(settings_.right_foot_frame_name);
128
129
  left_leg_settings.hip_from_waist =
130
      model_.jointPlacements[left_hip_id].translation();
131
  left_leg_settings.knee_from_hip =
132
      model_.jointPlacements[left_knee_id].translation();
133
  left_leg_settings.ankle_from_knee =
134
      model_.jointPlacements[left_ankle_id].translation();
135
  left_leg_settings.ankle_from_foot =
136
      -model_.frames[leftSoleID].placement.translation();
137
  left_leg_.initialize(left_leg_settings);
138
139
  right_leg_settings.hip_from_waist =
140
      model_.jointPlacements[right_hip_id].translation();
141
  right_leg_settings.knee_from_hip =
142
      model_.jointPlacements[right_knee_id].translation();
143
  right_leg_settings.ankle_from_knee =
144
      model_.jointPlacements[right_ankle_id].translation();
145
  right_leg_settings.ankle_from_foot =
146
      -model_.frames[rightSoleID].placement.translation();
147
  right_leg_.initialize(right_leg_settings);
148
149
  // Get the legs joints configuration for the test
150
  lleg_idx_qs_ = model_.idx_qs[left_hip_id];
151
  rleg_idx_qs_ = model_.idx_qs[right_hip_id];
152
}
153
154
pinocchio::SE3 BipedIG::computeBase(const Eigen::Vector3d &com,
155
                                    const Eigen::Matrix3d &baseRotation) {
156
  return pinocchio::SE3(baseRotation, com - baseRotation * com_from_waist_);
157
}
158
159
pinocchio::SE3 BipedIG::computeBase(const Eigen::Vector3d &com,
160
                                    const pinocchio::SE3 &leftFoot,
161
                                    const pinocchio::SE3 &rightFoot) {
162
  double leftYawl, rightYawl;
163
  leftYawl = pinocchio::log3(leftFoot.rotation())(2);
164
  rightYawl = pinocchio::log3(rightFoot.rotation())(2);
165
166
  return computeBase(com, Eigen::AngleAxisd((leftYawl + rightYawl) / 2,
167
                                            Eigen::Vector3d(0, 0, 1))
168
                              .toRotationMatrix());
169
}
170
171
void BipedIG::solve(const pinocchio::SE3 &base, const pinocchio::SE3 &leftFoot,
172
                    const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0,
173
                    Eigen::VectorXd &posture) {
174
  posture = q0;
175
  posture.head<3>() = base.translation();
176
  Eigen::Quaterniond quat(base.rotation());
177
  quat.normalize();
178
  posture.segment<4>(3) << quat.x(), quat.y(), quat.z(), quat.w();
179
180
  // Get the legs joints configuration for the test
181
  posture.segment<6>(lleg_idx_qs_) = left_leg_.solve(base, leftFoot);
182
  posture.segment<6>(rleg_idx_qs_) = right_leg_.solve(base, rightFoot);
183
}
184
185
void BipedIG::solve(const Eigen::Isometry3d &base,
186
                    const Eigen::Isometry3d &leftFoot,
187
                    const Eigen::Isometry3d &rightFoot,
188
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture) {
189
  pinocchio::SE3 root(base.matrix());
190
  pinocchio::SE3 LF(leftFoot.matrix());
191
  pinocchio::SE3 RF(rightFoot.matrix());
192
  solve(root, LF, RF, q0, posture);
193
}
194
195
void BipedIG::solve(const Eigen::Vector3d &com, const pinocchio::SE3 &leftFoot,
196
                    const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0,
197
                    Eigen::VectorXd &posture, const double &tolerance,
198
                    const int &max_iterations) {
199
  correctCoMfromWaist(com, leftFoot, rightFoot, q0, tolerance, max_iterations);
200
  pinocchio::SE3 base = computeBase(com, leftFoot, rightFoot);
201
  solve(base, leftFoot, rightFoot, q0, posture);
202
}
203
204
void BipedIG::solve(const Eigen::Vector3d &com,
205
                    const Eigen::Isometry3d &leftFoot,
206
                    const Eigen::Isometry3d &rightFoot,
207
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
208
                    const double &tolerance, const int &max_iterations) {
209
  pinocchio::SE3 LF(leftFoot.matrix());
210
  pinocchio::SE3 RF(rightFoot.matrix());
211
  solve(com, LF, RF, q0, posture, tolerance, max_iterations);
212
}
213
214
void BipedIG::solve(const Eigen::Vector3d &com,
215
                    const Eigen::Matrix3d &baseRotation,
216
                    const pinocchio::SE3 &leftFoot,
217
                    const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0,
218
                    Eigen::VectorXd &posture, const double &tolerance,
219
                    const int &max_iterations) {
220
  correctCoMfromWaist(com, leftFoot, rightFoot, q0, tolerance, max_iterations);
221
  pinocchio::SE3 base = computeBase(com, baseRotation);
222
  solve(base, leftFoot, rightFoot, q0, posture);
223
}
224
225
void BipedIG::solve(const Eigen::Vector3d &com,
226
                    const Eigen::Matrix3d &baseRotation,
227
                    const Eigen::Isometry3d &leftFoot,
228
                    const Eigen::Isometry3d &rightFoot,
229
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
230
                    const double &tolerance, const int &max_iterations) {
231
  pinocchio::SE3 LF(leftFoot.matrix());
232
  pinocchio::SE3 RF(rightFoot.matrix());
233
  solve(com, baseRotation, LF, RF, q0, posture, tolerance, max_iterations);
234
}
235
236
void BipedIG::derivatives(const Eigen::VectorXd &q1, const Eigen::VectorXd &q3,
237
                          Eigen::VectorXd &posture, Eigen::VectorXd &velocity,
238
                          Eigen::VectorXd &acceleration, const double &dt) {
239
  Eigen::VectorXd velocity1(pinocchio::difference(model_, q1, posture) / dt);
240
  Eigen::VectorXd velocity3(pinocchio::difference(model_, posture, q3) / dt);
241
242
  velocity = pinocchio::difference(model_, q1, q3) / (2 * dt);
243
  acceleration = (velocity3 - velocity1) / dt;
244
}
245
246
void BipedIG::solve(const std::array<pinocchio::SE3, 3> &bases,
247
                    const std::array<pinocchio::SE3, 3> &leftFeet,
248
                    const std::array<pinocchio::SE3, 3> &rightFeet,
249
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
250
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
251
                    const double &dt) {
252
  Eigen::VectorXd q1, q3;
253
  solve(bases[0], leftFeet[0], rightFeet[0], q0, q1);
254
  solve(bases[1], leftFeet[1], rightFeet[1], q0, posture);
255
  solve(bases[2], leftFeet[2], rightFeet[2], q0, q3);
256
257
  derivatives(q1, q3, posture, velocity, acceleration, dt);
258
}
259
260
void BipedIG::solve(const std::array<Eigen::Isometry3d, 3> &bases,
261
                    const std::array<Eigen::Isometry3d, 3> &leftFeet,
262
                    const std::array<Eigen::Isometry3d, 3> &rightFeet,
263
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
264
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
265
                    const double &dt) {
266
  Eigen::VectorXd q1, q3;
267
  solve(bases[0], leftFeet[0], rightFeet[0], q0, q1);
268
  solve(bases[1], leftFeet[1], rightFeet[1], q0, posture);
269
  solve(bases[2], leftFeet[2], rightFeet[2], q0, q3);
270
271
  derivatives(q1, q3, posture, velocity, acceleration, dt);
272
}
273
274
void BipedIG::solve(const std::array<Eigen::Vector3d, 3> &coms,
275
                    const std::array<pinocchio::SE3, 3> &leftFeet,
276
                    const std::array<pinocchio::SE3, 3> &rightFeet,
277
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
278
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
279
                    const double &dt, const double &tolerance,
280
                    const int &max_iterations) {
281
  Eigen::VectorXd q1, q3;
282
  solve(coms[0], leftFeet[0], rightFeet[0], q0, q1, tolerance, max_iterations);
283
  solve(coms[1], leftFeet[1], rightFeet[1], q0, posture, tolerance,
284
        max_iterations);
285
  solve(coms[2], leftFeet[2], rightFeet[2], q0, q3, tolerance, max_iterations);
286
287
  derivatives(q1, q3, posture, velocity, acceleration, dt);
288
}
289
290
void BipedIG::solve(const std::array<Eigen::Vector3d, 3> &coms,
291
                    const std::array<Eigen::Isometry3d, 3> &leftFeet,
292
                    const std::array<Eigen::Isometry3d, 3> &rightFeet,
293
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
294
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
295
                    const double &dt, const double &tolerance,
296
                    const int &max_iterations) {
297
  Eigen::VectorXd q1, q3;
298
  solve(coms[0], leftFeet[0], rightFeet[0], q0, q1, tolerance, max_iterations);
299
  solve(coms[1], leftFeet[1], rightFeet[1], q0, posture, tolerance,
300
        max_iterations);
301
  solve(coms[2], leftFeet[2], rightFeet[2], q0, q3, tolerance, max_iterations);
302
303
  derivatives(q1, q3, posture, velocity, acceleration, dt);
304
}  // @TODO: Include the parameter tolerance in each method solve. and
305
   // incorporate the correctCoMfromWaist in the methods solve.
306
307
void BipedIG::solve(const std::array<Eigen::Vector3d, 3> &coms,
308
                    const std::array<Eigen::Matrix3d, 3> &baseRotations,
309
                    const std::array<pinocchio::SE3, 3> &leftFeet,
310
                    const std::array<pinocchio::SE3, 3> &rightFeet,
311
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
312
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
313
                    const double &dt, const double &tolerance,
314
                    const int &max_iterations) {
315
  Eigen::VectorXd q1, q3;
316
  solve(coms[0], baseRotations[0], leftFeet[0], rightFeet[0], q0, q1, tolerance,
317
        max_iterations);
318
  solve(coms[1], baseRotations[1], leftFeet[1], rightFeet[1], q0, posture,
319
        tolerance, max_iterations);
320
  solve(coms[2], baseRotations[2], leftFeet[2], rightFeet[2], q0, q3, tolerance,
321
        max_iterations);
322
323
  derivatives(q1, q3, posture, velocity, acceleration, dt);
324
}
325
326
void BipedIG::solve(const std::array<Eigen::Vector3d, 3> &coms,
327
                    const std::array<Eigen::Matrix3d, 3> &baseRotations,
328
                    const std::array<Eigen::Isometry3d, 3> &leftFeet,
329
                    const std::array<Eigen::Isometry3d, 3> &rightFeet,
330
                    const Eigen::VectorXd &q0, Eigen::VectorXd &posture,
331
                    Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration,
332
                    const double &dt, const double &tolerance,
333
                    const int &max_iterations) {
334
  Eigen::VectorXd q1, q3;
335
  solve(coms[0], baseRotations[0], leftFeet[0], rightFeet[0], q0, q1, tolerance,
336
        max_iterations);
337
  solve(coms[1], baseRotations[1], leftFeet[1], rightFeet[1], q0, posture,
338
        tolerance, max_iterations);
339
  solve(coms[2], baseRotations[2], leftFeet[2], rightFeet[2], q0, q3, tolerance,
340
        max_iterations);
341
342
  derivatives(q1, q3, posture, velocity, acceleration, dt);
343
}
344
345
void BipedIG::set_com_from_waist(const Eigen::Vector3d &com_from_waist) {
346
  com_from_waist_ = com_from_waist;
347
}
348
349
void BipedIG::set_com_from_waist(const Eigen::VectorXd &q) {
350
  Eigen::Quaterniond baseRotation(q(6), q(3), q(4), q(5));
351
  Eigen::Vector3d com_from_waist =
352
      baseRotation.matrix().transpose() *
353
      (pinocchio::centerOfMass(model_, data_, q) - q.head(3));
354
  set_com_from_waist(com_from_waist);
355
}
356
357
void BipedIG::correctCoMfromWaist(const Eigen::Vector3d &com,
358
                                  const pinocchio::SE3 &leftFoot,
359
                                  const pinocchio::SE3 &rightFoot,
360
                                  const Eigen::VectorXd &q0,
361
                                  const double &tolerance,
362
                                  const int &max_iterations) {
363
  error_ << 1, 1, 1;
364
  baseRotation_temp_ = computeBase(com, leftFoot, rightFoot).rotation();
365
  int i = 0;
366
  while (error_.norm() > tolerance && i++ < max_iterations) {
367
    solve(com, leftFoot, rightFoot, q0, posture_temp_);
368
    com_temp_ = pinocchio::centerOfMass(model_, data_, posture_temp_);
369
    error_ = com_temp_ - com;
370
    com_from_waist_ += baseRotation_temp_.transpose() * (1.2 * error_);
371
  }
372
}
373
// @TODO: Use this function to initialize the posture reference
374
// @TODO: after some iterations, it converges geometrically. So, we can write
375
// the exact value from the convergence. by doing that, we can reduce the
376
// computation time and reduce the error. Or try An inner approximation.
377
378
void BipedIG::correctCoMfromWaist(const Eigen::Vector3d &com,
379
                                  const Eigen::Isometry3d &leftFoot,
380
                                  const Eigen::Isometry3d &rightFoot,
381
                                  const Eigen::VectorXd &q0,
382
                                  const double &tolerance,
383
                                  const int &max_iterations) {
384
  pinocchio::SE3 LF(leftFoot.matrix());
385
  pinocchio::SE3 RF(rightFoot.matrix());
386
  correctCoMfromWaist(com, LF, RF, q0, tolerance, max_iterations);
387
}
388
389
// DYNAMICS
390
391
void BipedIG::computeDynamics(const Eigen::VectorXd &posture,
392
                              const Eigen::VectorXd &velocity,
393
                              const Eigen::VectorXd &acceleration,
394
                              const Eigen::Matrix<double, 6, 1> &externalWrench,
395
                              bool flatHorizontalGround) {
396
  dynamics_.computeDynamics(posture, velocity, acceleration, externalWrench,
397
                            flatHorizontalGround);
398
}
399
400
void BipedIG::computeNL(const double &w, const Eigen::VectorXd &posture,
401
                        const Eigen::VectorXd &velocity,
402
                        const Eigen::VectorXd &acceleration,
403
                        const Eigen::Matrix<double, 6, 1> &externalWrench,
404
                        bool flatHorizontalGround) {
405
  dynamics_.computeNL(w, posture, velocity, acceleration, externalWrench,
406
                      flatHorizontalGround);
407
}
408
409
void BipedIG::computeNL(const double &w) {
410
  /**
411
   * In this function form, computeDynamics is suposed to have been called
412
   * before.
413
   */
414
  dynamics_.computeNL(w);
415
}
416
417
}  // namespace aig