param_funcs_evaluator.hpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Software License Agreement (BSD License) *
3  * Copyright (C) 2016 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 IWS_PARAM_FUNCS_EVALUATOR_H
34 #define IWS_PARAM_FUNCS_EVALUATOR_H
35 
36 #include <tuw_control/utils.h>
38 
39 namespace tuw
40 {
49 template <typename ObservedStateType, typename OutputStateType, typename ParamType, typename... ParamFuncs2StateTypes>
51 {
52  // special class member functions
53 public:
54  ParamFuncsEvaluator(std::shared_ptr<ParamType> _params)
55  : paramFuncs2State_(std::make_tuple(ParamFuncs2StateTypes(_params)...)), processingParamFuncs_(false)
56  {
57  }
58 
65 public:
66  template <typename ParamFuncPtrType>
67  std::shared_ptr<OutputStateType>& compute(std::shared_ptr<ObservedStateType>& _xObs, ParamFuncPtrType& _paramFuncs,
68  const double& _t)
69  {
70  auto& paramFuncs2State = std::get<Get_Tuple_Index<
71  ParamFuncPtrType, std::tuple<std::shared_ptr<typename ParamFuncs2StateTypes::ParamFuncType>...> >::value>(
73  auto& stateChDes = paramFuncs2State.compute(_xObs, _paramFuncs, _t);
74  if (paramFuncs2State.finished())
75  {
76  paramFuncs2State.reset();
77  processingParamFuncs_ = false;
78  }
79  return stateChDes;
80  }
85 public:
86  template <typename ParamFuncsType>
87  void loadParamFuncsState0(const std::vector<double>& _state0, const double& _timeShift = 0)
88  {
89  auto& paramFuncsI = std::get<ParamFuncsType>(paramFuncs2State_);
90  paramFuncsI.state0ParamFuncs_ = _state0;
91  paramFuncsI.timeShift_ = _timeShift;
92  paramFuncsI.reset();
93  }
96 public:
97  void reset()
98  {
100  {
101  _paramFuncs2StateI.reset();
102  });
103  }
106 public:
107  void reloadParam()
108  {
109  for_each_tuple(paramFuncs2State_, [](ParamFuncs2StateBase& _paramFuncs2StateI)
110  {
111  _paramFuncs2StateI.reloadParam();
112  });
113  }
114 
115 public:
116  std::tuple<ParamFuncs2StateTypes...> paramFuncs2State_;
117 public:
119 };
120 }
121 
122 #endif // IWS_PARAM_FUNCS_EVALUATOR_H
Class manipulating a set of parametric-functions-to-state objects based on requested parametric funct...
std::tuple< ParamFuncs2StateTypes... > paramFuncs2State_
Tuple storing the parametric functions evaluators.
ParamFuncsEvaluator(std::shared_ptr< ParamType > _params)
Helper function needed to upgrade c++ 2011.
Definition: utils.h:193
bool processingParamFuncs_
Flags if any evaluator is active.
constexpr std::enable_if< II==sizeof...(Tp), void >::type for_each_tuple(std::tuple< Tp... > &, FuncT)
Definition: utils.h:101
T & get(std::tuple< Args... > &t)
Definition: utils.h:222
static constexpr auto value
Definition: utils.h:205
virtual void reloadParam()=0
Reloads class parameters. To be called when parameters that influence the class variables are changed...
virtual void reset()=0
Resets class structures/variables.
std::shared_ptr< OutputStateType > & compute(std::shared_ptr< ObservedStateType > &_xObs, ParamFuncPtrType &_paramFuncs, const double &_t)
Performs a parametric functions evaluator computation step (calling the parametric functions evaluato...
void loadParamFuncsState0(const std::vector< double > &_state0, const double &_timeShift=0)
Loads the initial state into the specific parametric functions evaluators.
void reloadParam()
Calls reloadParam on all parametric functions evaluators.
void reset()
Resets all parametric functions evaluators.


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