sot-talos-balance  1.7.0
dummy-walking-pattern-generator.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Gepetto team, LAAS-CNRS
3  *
4  * This file is part of sot-talos-balance.
5  * sot-talos-balance is free software: you can redistribute it and/or
6  * modify it under the terms of the GNU Lesser General Public License
7  * as published by the Free Software Foundation, either version 3 of
8  * the License, or (at your option) any later version.
9  * sot-talos-balance 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
12  * GNU Lesser General Public License for more details. You should
13  * have received a copy of the GNU Lesser General Public License along
14  * with sot-talos-balance. If not, see <http://www.gnu.org/licenses/>.
15  */
16 
18 
19 #include <sot/core/debug.hh>
20 #include <dynamic-graph/factory.h>
21 #include <dynamic-graph/command-bind.h>
22 
23 #include <dynamic-graph/all-commands.h>
24 #include <sot/core/stop-watch.hh>
25 
26 namespace dynamicgraph
27 {
28  namespace sot
29  {
30  namespace talos_balance
31  {
32  namespace dg = ::dynamicgraph;
33  using namespace dg;
34  using namespace dg::command;
35 
36 //Size to be aligned "-------------------------------------------------------"
37 #define PROFILE_DUMMYWALKINGPATTERNGENERATOR_DCM_COMPUTATION "DummyWalkingPatternGenerator: dcm computation "
38 
39 #define INPUT_SIGNALS m_omegaSIN << m_rhoSIN << m_phaseSIN << m_footLeftSIN << m_footRightSIN << m_waistSIN << m_comSIN << m_vcomSIN << m_acomSIN << m_zmpSIN << m_referenceFrameSIN
40 
41 #define INNER_SIGNALS m_rfSINNER
42 
43 #define OUTPUT_SIGNALS m_comDesSOUT << m_vcomDesSOUT << m_acomDesSOUT << m_dcmDesSOUT << m_zmpDesSOUT << m_footLeftDesSOUT << m_footRightDesSOUT << m_waistDesSOUT << m_omegaDesSOUT << m_rhoDesSOUT << m_phaseDesSOUT
44 
47  typedef DummyWalkingPatternGenerator EntityClassName;
48 
49  /* --- DG FACTORY ---------------------------------------------------- */
50  DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(DummyWalkingPatternGenerator,
51  "DummyWalkingPatternGenerator");
52 
53  /* ------------------------------------------------------------------- */
54  /* --- CONSTRUCTION -------------------------------------------------- */
55  /* ------------------------------------------------------------------- */
57  : Entity(name)
58  , CONSTRUCT_SIGNAL_IN(omega, double)
59  , CONSTRUCT_SIGNAL_IN(rho, double)
60  , CONSTRUCT_SIGNAL_IN(phase, int)
61  , CONSTRUCT_SIGNAL_IN(footLeft, MatrixHomogeneous)
62  , CONSTRUCT_SIGNAL_IN(footRight, MatrixHomogeneous)
63  , CONSTRUCT_SIGNAL_IN(waist, MatrixHomogeneous)
64  , CONSTRUCT_SIGNAL_IN(com, dynamicgraph::Vector)
65  , CONSTRUCT_SIGNAL_IN(vcom, dynamicgraph::Vector)
66  , CONSTRUCT_SIGNAL_IN(acom, dynamicgraph::Vector)
67  , CONSTRUCT_SIGNAL_IN(zmp, dynamicgraph::Vector)
68  , CONSTRUCT_SIGNAL_IN(referenceFrame, MatrixHomogeneous)
69  , CONSTRUCT_SIGNAL_INNER(rf, MatrixHomogeneous, m_referenceFrameSIN)
70  , CONSTRUCT_SIGNAL_OUT(comDes, dynamicgraph::Vector, m_comSIN << m_rfSINNER)
71  , CONSTRUCT_SIGNAL_OUT(vcomDes, dynamicgraph::Vector, m_vcomSIN << m_rfSINNER)
72  , CONSTRUCT_SIGNAL_OUT(acomDes, dynamicgraph::Vector, m_acomSIN << m_rfSINNER)
73  , CONSTRUCT_SIGNAL_OUT(dcmDes, dynamicgraph::Vector, m_omegaSIN << m_comDesSOUT << m_vcomDesSOUT)
74  , CONSTRUCT_SIGNAL_OUT(zmpDes, dynamicgraph::Vector, m_omegaSIN << m_comDesSOUT << m_acomDesSOUT << m_rfSINNER << m_zmpSIN)
75  , CONSTRUCT_SIGNAL_OUT(footLeftDes, MatrixHomogeneous, m_footLeftSIN << m_rfSINNER)
76  , CONSTRUCT_SIGNAL_OUT(footRightDes, MatrixHomogeneous, m_footRightSIN << m_rfSINNER)
77  , CONSTRUCT_SIGNAL_OUT(waistDes, MatrixHomogeneous, m_waistSIN << m_rfSINNER)
78  , CONSTRUCT_SIGNAL_OUT(omegaDes, double, m_omegaSIN)
79  , CONSTRUCT_SIGNAL_OUT(rhoDes, double, m_rhoSIN)
80  , CONSTRUCT_SIGNAL_OUT(phaseDes, int, m_phaseSIN)
81  , m_initSucceeded(false)
82  {
83  Entity::signalRegistration( INPUT_SIGNALS << OUTPUT_SIGNALS );
84 
85  /* Commands. */
86  addCommand("init", makeCommandVoid0(*this, &DummyWalkingPatternGenerator::init, docCommandVoid0("Initialize the entity.")));
87  }
88 
90  {
91  return m.linear().transpose()*(v-m.translation());
92  }
93 
94  MatrixHomogeneous DummyWalkingPatternGenerator::actInv(MatrixHomogeneous m1, MatrixHomogeneous m2)
95  {
96  MatrixHomogeneous res;
97  res.linear() = m1.linear().transpose()*m2.linear();
98  res.translation() = m1.linear().transpose()*(m2.translation()-m1.translation());
99  return res;
100  }
101 
103  {
104  m_initSucceeded = true;
105  }
106 
107  /* ------------------------------------------------------------------- */
108  /* --- SIGNALS ------------------------------------------------------- */
109  /* ------------------------------------------------------------------- */
110 
111  DEFINE_SIGNAL_INNER_FUNCTION(rf, MatrixHomogeneous)
112  {
113  if(!m_initSucceeded)
114  {
115  SEND_WARNING_STREAM_MSG("Cannot compute signal rf before initialization!");
116  return s;
117  }
118 
119  s = m_referenceFrameSIN.isPlugged() ? m_referenceFrameSIN(iter) : MatrixHomogeneous::Identity();
120 
121  return s;
122  }
123 
125  {
126  if(!m_initSucceeded)
127  {
128  SEND_WARNING_STREAM_MSG("Cannot compute signal comDes before initialization!");
129  return s;
130  }
131  if(s.size()!=3)
132  s.resize(3);
133 
134  const Vector & com = m_comSIN(iter);
135  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
136 
137  assert( com.size()==3 && "Unexpected size of signal com" );
138 
139  s = actInv(referenceFrame, com);
140 
141  return s;
142  }
143 
145  {
146  if(!m_initSucceeded)
147  {
148  SEND_WARNING_STREAM_MSG("Cannot compute signal vcomDes before initialization!");
149  return s;
150  }
151  if(s.size()!=3)
152  s.resize(3);
153 
154  const Vector & vcom = m_vcomSIN(iter);
155  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
156 
157  assert( vcom.size()==3 && "Unexpected size of signal vcom" );
158 
159  s = referenceFrame.linear().transpose()*vcom;
160 
161  return s;
162  }
163 
165  {
166  if(!m_initSucceeded)
167  {
168  SEND_WARNING_STREAM_MSG("Cannot compute signal acomDes before initialization!");
169  return s;
170  }
171  if(s.size()!=3)
172  s.resize(3);
173 
174  const Vector & acom = m_acomSIN(iter);
175  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
176 
177  assert( acom.size()==3 && "Unexpected size of signal acom" );
178 
179  s = referenceFrame.linear().transpose()*acom;
180 
181  return s;
182  }
183 
185  {
186  if(!m_initSucceeded)
187  {
188  SEND_WARNING_STREAM_MSG("Cannot compute signal dcmDes before initialization!");
189  return s;
190  }
191  if(s.size()!=3)
192  s.resize(3);
193 
194  const double & omega = m_omegaSIN(iter);
195  const Vector & comDes = m_comDesSOUT(iter);
196  const Vector & vcomDes = m_vcomDesSOUT(iter);
197 
198  s = comDes + vcomDes/omega;
199 
200  return s;
201  }
202 
204  {
205  if(!m_initSucceeded)
206  {
207  SEND_WARNING_STREAM_MSG("Cannot compute signal zmpDes before initialization!");
208  return s;
209  }
210  if(s.size()!=3)
211  s.resize(3);
212 
213  Eigen::Vector3d zmpDes;
214 
215  if(m_zmpSIN.isPlugged())
216  {
217  const Vector & zmp = m_zmpSIN(iter);
218  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
219 
220  zmpDes[0] = zmp[0];
221  zmpDes[1] = zmp[1];
222  zmpDes[2] = zmp.size()>2 ? zmp[2] : 0.;
223 
224  zmpDes = actInv(referenceFrame, zmpDes);
225  }
226  else
227  {
228  const double & omega = m_omegaSIN(iter);
229  const Vector & comDes = m_comDesSOUT(iter);
230  const Vector & acomDes = m_acomDesSOUT(iter);
231 
232  zmpDes = comDes - acomDes/(omega*omega);
233  zmpDes[2] = 0.0;
234  }
235 
236  s = zmpDes;
237 
238  return s;
239  }
240 
241  DEFINE_SIGNAL_OUT_FUNCTION(footLeftDes, MatrixHomogeneous)
242  {
243  if(!m_initSucceeded)
244  {
245  SEND_WARNING_STREAM_MSG("Cannot compute signal footLeftDes before initialization!");
246  return s;
247  }
248 
249  MatrixHomogeneous footLeft = m_footLeftSIN(iter);
250 
251  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
252 
253  s = actInv(referenceFrame, footLeft);
254 
255  return s;
256  }
257 
258  DEFINE_SIGNAL_OUT_FUNCTION(footRightDes, MatrixHomogeneous)
259  {
260  if(!m_initSucceeded)
261  {
262  SEND_WARNING_STREAM_MSG("Cannot compute signal footRightDes before initialization!");
263  return s;
264  }
265 
266  MatrixHomogeneous footRight = m_footRightSIN(iter);
267 
268  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
269 
270  s = actInv(referenceFrame, footRight);
271 
272  return s;
273  }
274 
275  DEFINE_SIGNAL_OUT_FUNCTION(waistDes, MatrixHomogeneous)
276  {
277  if(!m_initSucceeded)
278  {
279  SEND_WARNING_STREAM_MSG("Cannot compute signal waistDes before initialization!");
280  return s;
281  }
282 
283  const MatrixHomogeneous & waist = m_waistSIN(iter);
284  const MatrixHomogeneous & referenceFrame = m_rfSINNER(iter);
285 
286  s = actInv(referenceFrame, waist);
287 
288  return s;
289  }
290 
291  DEFINE_SIGNAL_OUT_FUNCTION(omegaDes, double)
292  {
293  if(!m_initSucceeded)
294  {
295  SEND_WARNING_STREAM_MSG("Cannot compute signal omegaDes before initialization!");
296  return s;
297  }
298 
299  s = m_omegaSIN(iter);
300  return s;
301  }
302 
304  {
305  if(!m_initSucceeded)
306  {
307  SEND_WARNING_STREAM_MSG("Cannot compute signal rhoDes before initialization!");
308  return s;
309  }
310 
311  s = m_rhoSIN(iter);
312  return s;
313  }
314 
316  {
317  if(!m_initSucceeded)
318  {
319  SEND_WARNING_STREAM_MSG("Cannot compute signal phaseDes before initialization!");
320  return s;
321  }
322 
323  s = m_phaseSIN(iter);
324  return s;
325  }
326 
327  /* --- COMMANDS ---------------------------------------------------------- */
328 
329  /* ------------------------------------------------------------------- */
330  /* --- ENTITY -------------------------------------------------------- */
331  /* ------------------------------------------------------------------- */
332 
333  void DummyWalkingPatternGenerator::display(std::ostream& os) const
334  {
335  os << "DummyWalkingPatternGenerator " << getName();
336  try
337  {
338  getProfiler().report_all(3, os);
339  }
340  catch (ExceptionSignal e) {}
341  }
342  } // namespace talos_balance
343  } // namespace sot
344 } // namespace dynamicgraph
345 
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hh:40
DYNAMICGRAPH_FACTORY_ENTITY_PLUGIN(AdmittanceControllerEndEffector, "AdmittanceControllerEndEffector")
EIGEN_MAKE_ALIGNED_OPERATOR_NEW DummyWalkingPatternGenerator(const std::string &name)
DEFINE_SIGNAL_INNER_FUNCTION(w_force, dynamicgraph::Vector)
dynamicgraph::Vector actInv(MatrixHomogeneous m, dynamicgraph::Vector v)
true if the entity has been successfully initialized