GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: src/step-computer-pos.cpp Lines: 0 115 0.0 %
Date: 2023-06-05 08:59:09 Branches: 0 274 0.0 %

Line Branch Exec Source
1
/*+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
2
 * Copyright Projet JRL-Japan, 2007
3
 *+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
4
 *
5
 * File:      StepComputer.cpp
6
 * Project:   SOT
7
 * Author:    Paul Evrard, Nicolas Mansard
8
 *
9
 * Version control
10
 * ===============
11
 *
12
 *  $Id$
13
 *
14
 * Description
15
 * ============
16
 *
17
 *
18
 * ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++*/
19
20
#include <time.h>
21
22
#include <cmath>
23
#ifndef WIN32
24
#include <sys/time.h>
25
26
#include <iostream>
27
#else
28
#include <Winsock2.h>
29
30
#include <jrl/mal/boost.hh>
31
#include <sot/core/utils-windows.hh>
32
#endif /*WIN32*/
33
34
#include <dynamic-graph/factory.h>
35
#include <dynamic-graph/pool.h>
36
#include <sot/pattern-generator/exception-pg.h>
37
#include <sot/pattern-generator/step-checker.h>
38
#include <sot/pattern-generator/step-computer-pos.h>
39
#include <sot/pattern-generator/step-queue.h>
40
41
#include <sot/core/debug.hh>
42
#include <sot/core/macros-signal.hh>
43
44
namespace dynamicgraph {
45
namespace sot {
46
47
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(StepComputerPos, "StepComputerPos");
48
49
StepComputerPos::StepComputerPos(const std::string &name)
50
    : Entity(name),
51
      referencePositionLeftSIN(
52
          NULL, "StepComputerPos(" + name + ")::input(vector)::posrefleft"),
53
      referencePositionRightSIN(
54
          NULL, "StepComputerPos(" + name + ")::input(vector)::posrefright"),
55
      contactFootSIN(NULL,
56
                     "StepComputerPos(" + name + ")::input(uint)::contactfoot"),
57
      rfMref0(),
58
      lfMref0(),
59
      twoHandObserver(0x0),
60
      checker(),
61
      logChanges("/tmp/stepcomp_changes.dat"),
62
      logPreview("/tmp/stepcomp_preview.dat") {
63
  sotDEBUGIN(5);
64
65
  signalRegistration(referencePositionLeftSIN << referencePositionRightSIN
66
                                              << contactFootSIN);
67
68
  sotDEBUGOUT(5);
69
}
70
71
void StepComputerPos::nextStep(StepQueue &queue, int timeCurr) {
72
  // Introduce new step at the end of the preview window.
73
  if (queue.getLastStep().contact == CONTACT_LEFT_FOOT) {
74
    queue.pushStep(0., -queue.getZeroStepPosition(), 0.);
75
    logPreview << timeCurr << " " << 0 << " " << -queue.getZeroStepPosition()
76
               << " " << 0 << std::endl;
77
  } else {
78
    queue.pushStep(0., queue.getZeroStepPosition(), 0.);
79
    logPreview << timeCurr << " " << 0 << " " << queue.getZeroStepPosition()
80
               << " " << 0 << std::endl;
81
  }
82
}
83
84
void StepComputerPos::changeFirstStep(StepQueue &queue, int timeCurr) {
85
  if (!twoHandObserver) {
86
    std::cerr << "Observer not set" << std::endl;
87
    return;
88
  }
89
90
  const unsigned &sfoot = contactFootSIN(timeCurr);
91
  const MatrixHomogeneous &wMlf =
92
      twoHandObserver->leftFootPositionSIN.access(timeCurr);
93
  const MatrixHomogeneous &wMrf =
94
      twoHandObserver->rightFootPositionSIN.access(timeCurr);
95
96
  // actual and reference position of reference frame in fly foot,
97
  // position of fly foot in support foot.
98
99
  MatrixHomogeneous ffMref, ffMref0;
100
  MatrixHomogeneous sfMff;
101
  if (sfoot != 1)  // --- left foot support ---
102
  {
103
    ffMref = referencePositionRightSIN.access(timeCurr);
104
    ffMref0 = rfMref0;
105
    MatrixHomogeneous sfMw;
106
    sfMw = wMlf.inverse();
107
    sfMff = sfMw * wMrf;
108
  } else  // -- right foot support ---
109
  {
110
    ffMref = referencePositionLeftSIN.access(timeCurr);
111
    ffMref0 = lfMref0;
112
    MatrixHomogeneous sfMw;
113
    sfMw = wMrf.inverse();
114
    sfMff = sfMw * wMlf;
115
  }
116
117
  // homogeneous transform from ref position of ref frame to
118
  // actual position of ref frame.
119
120
  MatrixHomogeneous ref0Mff;
121
  ref0Mff = ffMref0.inverse();
122
  MatrixHomogeneous ref0Mref;
123
  ref0Mref = ref0Mff * ffMref;
124
125
  // extract the translation part and express it in the support
126
  // foot frame.
127
128
  MatrixHomogeneous sfMref0;
129
  sfMref0 = sfMff * ffMref0;
130
  Vector t_ref0(3);
131
  t_ref0 = ref0Mref.translation();
132
  MatrixRotation sfRref0;
133
  sfRref0 = sfMref0.linear();
134
  Vector t_sf = sfRref0 * t_ref0;
135
136
  // add it to the position of the fly foot in support foot to
137
  // get the new position of fly foot in support foot.
138
139
  Vector pff_sf(3);
140
  pff_sf = sfMff.translation();
141
  t_sf += pff_sf;
142
143
  // compute the rotation that transforms ref0 into ref,
144
  // express it in the support foot frame. Then get the
145
  // associated yaw (rot around z).
146
147
  MatrixRotation ref0Rsf;
148
  ref0Rsf = sfRref0.transpose();
149
  MatrixRotation ref0Rref;
150
  ref0Rref = ref0Mref.linear();
151
  MatrixRotation tmp;
152
  tmp = ref0Rref * ref0Rsf;
153
  MatrixRotation Rref;
154
  Rref = sfRref0 * tmp;
155
  VectorRollPitchYaw rpy;
156
  rpy = (Rref.eulerAngles(2, 1, 0)).reverse();
157
158
  // get the yaw of the current orientation of the ff wrt sf.
159
  // Add it to the previously computed rpy.
160
161
  MatrixRotation sfRff;
162
  sfRff = sfMff.linear();
163
  VectorRollPitchYaw rpy_ff;
164
  rpy_ff = (sfRff.eulerAngles(2, 1, 0)).reverse();
165
  rpy += rpy_ff;
166
167
  // The clipping function expects the x-y coordinates of the
168
  // destination fly foot in the support foot frame.
169
170
  double x = t_sf(0), y = t_sf(1);
171
  double theta = rpy(2) * 180 / 3.14159265;
172
173
  const double THETA_MAX = 9.;
174
  if (theta < -THETA_MAX) {
175
    theta = -THETA_MAX;
176
  }
177
  if (theta > THETA_MAX) {
178
    theta = THETA_MAX;
179
  }
180
181
  double nx = 0, ny = 0;
182
  if (sfoot != 1) {  // left foot support phase
183
    if (y > 0) {
184
      y = -0.001;
185
    }
186
  } else {
187
    if (y < 0) {
188
      y = 0.001;
189
    }
190
  }
191
192
  checker.clipStep(x, y, nx, ny);
193
194
  // Log x-y values before and after clipping
195
196
  logChanges << timeCurr << " " << x << " " << y << " " << nx << " " << ny
197
             << " ";
198
199
  // The coordinates must be expressed in the destination foot frame.
200
  // See the technical report of Olivier Stasse for more details,
201
  // on top of page 79.
202
203
  double theta_rad = 3.14159265 * theta / 180.;
204
  double ctheta = cos(theta_rad);
205
  double stheta = sin(theta_rad);
206
207
  x = nx * ctheta + ny * stheta;
208
  y = -nx * stheta + ny * ctheta;
209
210
  queue.changeFirstStep(x, y, theta);
211
212
  // Log the step
213
214
  logChanges << x << " " << y << " " << theta << std::endl;
215
}
216
217
void StepComputerPos::thisIsZero() {
218
  sotDEBUGIN(15);
219
220
  rfMref0 = referencePositionRightSIN.accessCopy();
221
  lfMref0 = referencePositionLeftSIN.accessCopy();
222
223
  sotDEBUGOUT(15);
224
}
225
226
void StepComputerPos::display(std::ostream &os) const {
227
  os << "StepComputerPos <" << getName() << ">:" << std::endl;
228
}
229
230
void StepComputerPos::commandLine(const std::string &cmdLine,
231
                                  std::istringstream &cmdArgs,
232
                                  std::ostream &os) {
233
  if (cmdLine == "help") {
234
    os << "NextStep: " << std::endl
235
       << " - setObserver" << std::endl
236
       << " - thisIsZero {record|disp}" << std::endl
237
       << std::endl;
238
  } else if (cmdLine == "thisIsZero") {
239
    std::string arg;
240
    cmdArgs >> arg;
241
    if (arg == "disp_left") {
242
      os << "zero_left = " << lfMref0;
243
    } else if (arg == "disp_right") {
244
      os << "zero_right = " << rfMref0;
245
    } else if (arg == "record") {
246
      thisIsZero();
247
    }
248
  } else if (cmdLine == "setObserver") {
249
    std::string name = "stepobs";
250
    cmdArgs >> std::ws;
251
    if (cmdArgs.good()) {
252
      cmdArgs >> name;
253
    }
254
    Entity *entity = &(PoolStorage::getInstance()->getEntity(name));
255
    twoHandObserver = dynamic_cast<StepObserver *>(entity);
256
  } else {
257
  }
258
}
259
260
}  // namespace sot
261
}  // namespace dynamicgraph