edge8_lattices.hpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2017 by Horatiu George Todoran <todorangrg@gmail.com> *
4  * *
5  * Redistribution and use in source and binary forms, with or without *
6  * modification, are permitted provided that the following conditions *
7  * are met: *
8  * *
9  * 1. Redistributions of source code must retain the above copyright *
10  * notice, this list of conditions and the following disclaimer. *
11  * 2. Redistributions in binary form must reproduce the above copyright *
12  * notice, this list of conditions and the following disclaimer in *
13  * the documentation and/or other materials provided with the *
14  * distribution. *
15  * 3. Neither the name of the copyright holder nor the names of its *
16  * contributors may be used to endorse or promote products derived *
17  * from this software without specific prior written permission. *
18  * *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT *
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS *
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE *
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, *
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, *
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; *
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER *
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT *
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY *
29  * WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE *
30  * POSSIBILITY OF SUCH DAMAGE. *
31  ***************************************************************************/
32 
33 #ifndef EDGE8_LATTICES_HPP
34 #define EDGE8_LATTICES_HPP
35 
38 #include <tuw_control/utils.h>
39 
40 namespace tuw
41 {
42 template <typename TNumType, class TSimType, class... TCostFuncsType>
43 class LatticeTypeStateSimBeginEnd
44  : public LatticeTypeBaseCRTP<LatticeTypeStateSimBeginEnd<TNumType, TSimType, TCostFuncsType...>, TNumType, TSimType,
45  TCostFuncsType...>
46 {
47 public:
48  using LatticeTypeBaseCRTP<LatticeTypeStateSimBeginEnd, TNumType, TSimType, TCostFuncsType...>::LatticeTypeBaseCRTP;
49 
50 public:
51  static void computeLatticeArcsImpl(TSimType& _sim, std::vector<TNumType>& _latticeArcs)
52  {
53  _latticeArcs.resize(1);
54  _latticeArcs[0] = _sim.paramStruct->paramFuncs.funcsArcEnd();
55  }
56 
57 public:
58  void computeDArcIdPImpl(const TSimType& _sim, const TNumType _arc, const size_t& _lattIdx, auto& _dstStateGrad)
59  {
60  auto& dstStateGradCf = _dstStateGrad.stateCf();
61  auto& dstStateGradNm = _dstStateGrad.stateNm();
62  size_t optParamTBackIdx = dstStateGradCf.sub(0).data().size() - 1;
63  dstStateGradCf.mat().col(optParamTBackIdx) += _sim.stateCfDotCache().data();
64  dstStateGradNm.mat().col(optParamTBackIdx) += _sim.stateNmDotCache().data();
65  }
66 
67 public:
68  virtual void precompute(TSimType& _sim) override
69  {
70  }
71 };
72 
73 template <typename TNumType, class TSimType, class... TCostFuncsType>
75  : public LatticeTypeBaseCRTP<LatticeTypeStateSimEqDt<TNumType, TSimType, TCostFuncsType...>, TNumType, TSimType,
76  TCostFuncsType...>
77 {
78 public:
79  using LatticeTypeBaseCRTP<LatticeTypeStateSimEqDt, TNumType, TSimType, TCostFuncsType...>::LatticeTypeBaseCRTP;
80 
81 public:
82  void computeLatticeArcsImpl(TSimType& _sim, std::vector<TNumType>& _latticeArcs) const
83  {
84  const TNumType arcParamMax = _sim.paramStruct->paramFuncs.funcsArcEnd();
85  double dt = dt_;
86  if (nrPts_ >= 1)
87  {
88  dt = arcParamMax / (TNumType)(nrPts_);
89  }
90  // const size_t latticeSize = std::max( 0, (int)( ceil( arcParamMax / dt ) ) );
91  // if(latticeSize != _latticeArcs.size()) { _latticeArcs.resize( latticeSize ); }
92  // for ( size_t i = 0; i < latticeSize; ++i ) { _latticeArcs[i] = (i+1) * dt; }
93  // _latticeArcs.back() = arcParamMax;
94 
95  if ((int)_latticeArcs.size() != nrPts_)
96  {
97  _latticeArcs.resize(nrPts_);
98  }
99  for (int i = 0; i < nrPts_; ++i)
100  {
101  _latticeArcs[i] = (i + 1) * dt;
102  }
103  _latticeArcs.back() = arcParamMax;
104  }
105 
106 public:
107  void computeDArcIdPImpl(const TSimType& _sim, const TNumType _arc, const size_t& _lattIdx, auto& _dstStateGrad)
108  {
109  // if (nrPts_ > 1) {
110  auto& dstStateGradCf = _dstStateGrad.stateCf();
111  auto& dstStateGradNm = _dstStateGrad.stateNm();
112 
113  const TNumType dtIdpEnd = (TNumType)(_lattIdx + 1) / (TNumType)(this->lattice.size() /*-1*/);
114  size_t optParamTBackIdx = dstStateGradCf.sub(0).data().size() - 1;
115 
116  dstStateGradCf.mat().col(optParamTBackIdx) += _sim.stateCfDotCache().data() * dtIdpEnd;
117  dstStateGradNm.mat().col(optParamTBackIdx) += _sim.stateNmDotCache().data() * dtIdpEnd;
118  // }
119  }
120 
121 public:
122  virtual void precompute(TSimType& _sim) override
123  {
124  }
125 
126 public:
127  const TNumType& dt()
128  {
129  return dt_;
130  }
131 
132 public:
133  void setDt(const TNumType& _dt)
134  {
135  dt_ = _dt;
136  nrPts_ = -1;
137  }
138 
139 public:
140  void setNrPts(const size_t& _nrPts)
141  {
142  nrPts_ = _nrPts;
143  }
144 
145 private:
146  TNumType dt_;
147 
148 private:
149  int nrPts_;
150 };
151 
152 template <typename TNumType, class TSimType, class... TCostFuncsType>
154  : public LatticeTypeBaseCRTP<LatticeTypeStateSimEqDs<TNumType, TSimType, TCostFuncsType...>, TNumType, TSimType,
155  TCostFuncsType...>
156 {
157 public:
158  using LatticeTypeBaseCRTP<LatticeTypeStateSimEqDs, TNumType, TSimType, TCostFuncsType...>::LatticeTypeBaseCRTP;
159 
160 public:
161  struct CosSinCache
162  {
163  TNumType cos;
164  TNumType sin;
165  };
166 
167 public:
168  std::vector<CosSinCache> cosSinCache_;
169 
170 public:
171  void computeLatticeArcsImpl(TSimType& _sim, std::vector<TNumType>& _latticeArcs)
172  {
173  auto& paramFuncs = _sim.paramStruct->paramFuncs;
174  double sEnd;
175  if (nrPts_ > 1)
176  {
177  paramFuncs.setEvalArc(paramFuncs.funcsArcEnd());
178  sEnd = paramFuncs.computeS();
179  ds_ = sEnd / (TNumType)(nrPts_);
180  paramFuncs.setEvalArc(paramFuncs.funcsArcBegin());
181  if ((int)_latticeArcs.size() != nrPts_)
182  {
183  _latticeArcs.resize(nrPts_);
184  cosSinCache_.resize(nrPts_);
185  }
186  for (int i = 0; i < nrPts_; ++i)
187  {
188  _latticeArcs[i] = (i + 1) * ds_;
189  }
190  _latticeArcs.back() = sEnd;
191  paramFuncs.computeS2TLattice(_latticeArcs, _latticeArcs);
192  }
193  }
194 
195 public:
196  void computeDArcIdPImpl(const TSimType& _sim, const TNumType _arc, const size_t& _lattIdx, auto& _dstStateGrad)
197  {
198  if (nrPts_ > 1)
199  {
200  if (_lattIdx == 0)
201  {
202  TNumType tEnd = _sim.paramStruct->paramFuncs.funcsArcEnd();
203  auto& simNonConst = const_cast<TSimType&>(_sim);
204  simNonConst.setXCf(tEnd, PfEaG::NONE);
205  simNonConst.setGradXCf(tEnd, PfEaG::NEAR_LAST);
206  simNonConst.setXCfDot(tEnd, PfEaG::NEAR_LAST);
207 
208  dsdp = _sim.state().stateGradCf().s().data();
209  dsdp(dsdp.rows() - 1) += _sim.stateCfDotCache().s();
210 
211  simNonConst.setXCf(_arc, PfEaG::AT_BEGIN);
212  simNonConst.setGradXCf(_arc, PfEaG::NEAR_LAST);
213  simNonConst.setXCfDot(_arc, PfEaG::NEAR_LAST);
214  stateDotCache.resize(_sim.stateNmDotCache().data().size() + _sim.stateCfDotCache().data().size());
215  }
216  stateDotCache.block(0, 0, _sim.stateNmDotCache().data().size(), 1) = _sim.stateNmDotCache().data();
217  stateDotCache.block(_sim.stateNmDotCache().data().size(), 0, _sim.stateCfDotCache().data().size(), 1) =
218  _sim.stateCfDotCache().data();
219  auto& v = _sim.state().stateCf().v();
220  if (fabs(v) > 1e-4)
221  {
222  TNumType iByNS = (TNumType)(_lattIdx + 1) /
223  (TNumType)(this->lattice.size() /*-1*/) /*_sim.state().stateCf().s() / (ds_*nrPts_)*/;
224  _dstStateGrad.mat() += (stateDotCache) * ((iByNS * dsdp - _dstStateGrad.stateCf().s().data()) / v).transpose();
225  }
226  }
227  }
228 
229 public:
230  virtual void precompute(TSimType& _sim) override
231  {
232  for (size_t i = 0; i < cosSinCache_.size(); ++i)
233  {
234  const TNumType& th = this->lattice[i].statePtr->stateNm().theta();
235  cosSinCache_[i].cos = cos(th);
236  cosSinCache_[i].sin = sin(th);
237  }
238  }
239 
240 public:
241  const TNumType& dt()
242  {
243  return ds_;
244  }
245 
246 public:
247  void setDs(const TNumType& _ds)
248  {
249  ds_ = _ds;
250  nrPts_ = -1;
251  }
252 
253 public:
254  void setNrPts(const size_t& _nrPts)
255  {
256  nrPts_ = _nrPts;
257  }
258 
259 public:
260  TNumType ds_;
261 
262 private:
263  int nrPts_;
264 
265 private:
266  Eigen::Matrix<TNumType, -1, 1> dsdp;
267 
268 private:
269  Eigen::Matrix<TNumType, -1, 1> stateDotCache;
270 };
271 
272 template <typename TNumType, class TSimType, class... TCostFuncsType>
274  : public LatticeTypeBaseCRTP<LatticeTypeStateSimCtrlPtKnotsP<TNumType, TSimType, TCostFuncsType...>, TNumType,
275  TSimType, TCostFuncsType...>
276 {
277 public:
278  using LatticeTypeBaseCRTP<LatticeTypeStateSimCtrlPtKnotsP, TNumType, TSimType,
279  TCostFuncsType...>::LatticeTypeBaseCRTP;
280 
281 public:
282  void computeLatticeArcsImpl(TSimType& _sim, std::vector<TNumType>& _latticeArcs) const
283  {
284  if (inUse)
285  {
286  _latticeArcs.resize(_sim.paramStruct->paramFuncs.funcsArcSize(1) - 2);
287  auto& paramFuncs = _sim.paramStruct->paramFuncs;
288  for (size_t i = 0; i < _latticeArcs.size(); ++i)
289  {
290  _latticeArcs[i] = paramFuncs.funcsArc(1, i + 1);
291  }
292  }
293  else
294  {
295  _latticeArcs.clear();
296  }
297  }
298 
299 public:
300  void computeDArcIdPImpl(const TSimType& _sim, const TNumType _arc, const size_t& _lattIdx, auto& _dstStateGrad)
301  {
302  if (inUse)
303  {
304  auto& dstStateGradCf = _dstStateGrad.stateCf();
305  auto& dstStateGradNm = _dstStateGrad.stateNm();
306  size_t optParamTIdx =
307  dstStateGradCf.sub(0).optParamV().data().size() + dstStateGradCf.sub(0).optParamP().data().size();
308  dstStateGradCf.mat().col(optParamTIdx + _lattIdx) += _sim.stateCfDotCache().data();
309  dstStateGradNm.mat().col(optParamTIdx + _lattIdx) += _sim.stateNmDotCache().data();
310  }
311  }
312 
313 public:
314  virtual void precompute(TSimType& _sim) override
315  {
316  }
317 
318 public:
319  bool inUse;
320 };
321 
322 template <typename TNumType, class TSimType, class... TCostFuncsType>
324  : public LatticeTypeBaseCRTP<LatticeTypeStateSimCtrlPtKnotsV<TNumType, TSimType, TCostFuncsType...>, TNumType,
325  TSimType, TCostFuncsType...>
326 {
327 public:
328  using LatticeTypeBaseCRTP<LatticeTypeStateSimCtrlPtKnotsV, TNumType, TSimType,
329  TCostFuncsType...>::LatticeTypeBaseCRTP;
330 
331 public:
332  void computeLatticeArcsImpl(TSimType& _sim, std::vector<TNumType>& _latticeArcs) const
333  {
334  if (inUse)
335  {
336  _latticeArcs.resize(_sim.paramStruct->paramFuncs.funcsArcSize(0) - 1);
337  auto& paramFuncs = _sim.paramStruct->paramFuncs;
338  for (size_t i = 0; i < _latticeArcs.size(); ++i)
339  {
340  _latticeArcs[i] = paramFuncs.funcsArc(0, i + 1);
341  }
342  }
343  else
344  {
345  _latticeArcs.clear();
346  }
347  }
348 
349 public:
350  void computeDArcIdPImpl(const TSimType& _sim, const TNumType _arc, const size_t& _lattIdx, auto& _dstStateGrad)
351  {
352  if (inUse)
353  {
354  auto& dstStateGradCf = _dstStateGrad.stateCf();
355  auto& dstStateGradNm = _dstStateGrad.stateNm();
356  size_t optParamTIdx = dstStateGradCf.sub(0).optParamV().data().size() +
357  dstStateGradCf.sub(0).optParamP().data().size() +
358  dstStateGradCf.sub(0).optParamTP().data().size();
359  dstStateGradCf.mat().col(optParamTIdx + _lattIdx) += _sim.stateCfDotCache().data();
360  dstStateGradNm.mat().col(optParamTIdx + _lattIdx) += _sim.stateNmDotCache().data();
361  }
362  }
363 
364 public:
365  virtual void precompute(TSimType& _sim) override
366  {
367  }
368 
369 public:
370  bool inUse;
371 };
372 }
373 
374 #endif // EDGE8_LATTICES_HPP
virtual void precompute(TSimType &_sim) override
static void computeLatticeArcsImpl(TSimType &_sim, std::vector< TNumType > &_latticeArcs)
void setDt(const TNumType &_dt)
void setNrPts(const size_t &_nrPts)
virtual void precompute(TSimType &_sim) override
void computeDArcIdPImpl(const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
void computeLatticeArcsImpl(TSimType &_sim, std::vector< TNumType > &_latticeArcs) const
void computeLatticeArcsImpl(TSimType &_sim, std::vector< TNumType > &_latticeArcs) const
void setDs(const TNumType &_ds)
void computeDArcIdPImpl(const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
void computeLatticeArcsImpl(TSimType &_sim, std::vector< TNumType > &_latticeArcs)
void setNrPts(const size_t &_nrPts)
void computeLatticeArcsImpl(TSimType &_sim, std::vector< TNumType > &_latticeArcs) const
virtual void precompute(TSimType &_sim) override
void computeDArcIdPImpl(const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
std::vector< CosSinCache > cosSinCache_
virtual void precompute(TSimType &_sim) override
close to previous evaluation arc
void computeDArcIdPImpl(const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
void computeDArcIdPImpl(const TSimType &_sim, const TNumType _arc, const size_t &_lattIdx, auto &_dstStateGrad)
this evaluation arc is at the arc parametrization begin
virtual void precompute(TSimType &_sim) override


tuw_control
Author(s): George Todoran
autogenerated on Mon Jun 10 2019 15:27:21