discretization_options.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 DISCRETIZATION_OPTIONS_HPP
34 #define DISCRETIZATION_OPTIONS_HPP
35 
36 #include <float.h>
37 #include <memory>
38 #include <array>
39 
40 #include <boost/numeric/odeint.hpp>
41 #include <boost/array.hpp>
42 
43 #include <algorithm>
44 
45 namespace tuw
46 {
47 namespace odeint = boost::numeric::odeint;
48 
49 template <class TValue = double>
50 struct rk4_38_abc
51 {
52  static constexpr const size_t stageNr = 4;
53  static constexpr const boost::array<TValue, 1> a1 = { { +1.0 / 3.0 } };
54  static constexpr const boost::array<TValue, 2> a2 = { { -1.0 / 3.0, +1.0 } };
55  static constexpr const boost::array<TValue, 3> a3 = { { +1.0, -1.0, +1.0 } };
56  static constexpr const boost::array<TValue, stageNr> b = { { +1.0 / 8.0, +3.0 / 8.0, +3.0 / 8.0, +1.0 / 8.0 } };
57  static constexpr const boost::array<TValue, stageNr> c = { { +0.0, +1.0 / 3.0, +2.0 / 3.0, +1.0 } };
58  static auto a()
59  {
60  return std::move(boost::fusion::make_vector(a1, a2, a3));
61  }
62 };
63 template <class Value>
64 constexpr const boost::array<Value, 1> rk4_38_abc<Value>::a1;
65 template <class Value>
66 constexpr const boost::array<Value, 2> rk4_38_abc<Value>::a2;
67 template <class Value>
68 constexpr const boost::array<Value, 3> rk4_38_abc<Value>::a3;
69 template <class Value>
70 constexpr const boost::array<Value, rk4_38_abc<Value>::stageNr> rk4_38_abc<Value>::b;
71 template <class Value>
72 constexpr const boost::array<Value, rk4_38_abc<Value>::stageNr> rk4_38_abc<Value>::c;
73 
74 template <class TValue = double>
75 struct heun_abc
76 {
77  static constexpr const size_t stageNr = 2;
78  static constexpr const boost::array<TValue, 1> a1 = { { 1.0 / 2.0 } };
79  static constexpr const boost::array<TValue, stageNr> b = { { 0.0, 1.0 } };
80  static constexpr const boost::array<TValue, stageNr> c = { { 0.0, 1.0 / 2.0 } };
81  static auto a()
82  {
83  return std::move(boost::fusion::make_vector(a1));
84  }
85 };
86 template <class Value>
87 constexpr const boost::array<Value, 1> heun_abc<Value>::a1;
88 template <class Value>
89 constexpr const boost::array<Value, heun_abc<Value>::stageNr> heun_abc<Value>::b;
90 template <class Value>
91 constexpr const boost::array<Value, heun_abc<Value>::stageNr> heun_abc<Value>::c;
92 
93 template <class TValue = double>
94 struct euler_abc
95 {
96  static constexpr const size_t stageNr = 1;
97  static constexpr const boost::array<TValue, 0> a1 = { {} };
98  static constexpr const boost::array<TValue, stageNr> b = { { 1.0 } };
99  static constexpr const boost::array<TValue, stageNr> c = { { 1.0 } };
100  static auto a()
101  {
102  return std::move(boost::fusion::make_vector());
103  }
104 };
105 template <class Value>
106 constexpr const boost::array<Value, 0> euler_abc<Value>::a1;
107 template <class Value>
108 constexpr const boost::array<Value, euler_abc<Value>::stageNr> euler_abc<Value>::b;
109 template <class Value>
110 constexpr const boost::array<Value, euler_abc<Value>::stageNr> euler_abc<Value>::c;
111 
112 template <template <class> class MethodType, class State, class Value = double, class Deriv = State, class Time = Value,
113  class Algebra = odeint::range_algebra, class Operations = odeint::default_operations,
114  class Resizer = odeint::initially_resizer>
116  : public odeint::explicit_generic_rk<MethodType<Value>::stageNr, MethodType<Value>::stageNr, State, Value, Deriv,
117  Time, Algebra, Operations, Resizer>
118 {
119 public:
120  using stepper_base_type = odeint::explicit_generic_rk<MethodType<Value>::stageNr, MethodType<Value>::stageNr, State,
121  Value, Deriv, Time, Algebra, Operations, Resizer>;
122  using state_type = typename stepper_base_type::state_type;
123  using wrapped_state_type = typename stepper_base_type::wrapped_state_type;
124  using value_type = typename stepper_base_type::value_type;
125  using deriv_type = typename stepper_base_type::deriv_type;
126  using wrapped_deriv_type = typename stepper_base_type::wrapped_deriv_type;
127  using time_type = typename stepper_base_type::time_type;
128  using algebra_type = typename stepper_base_type::algebra_type;
129  using operations_type = typename stepper_base_type::operations_type;
130  using resizer_type = typename stepper_base_type::resizer_type;
131  using stepper_type = typename stepper_base_type::stepper_type;
132 
134  : stepper_base_type(MethodType<Value>::a(), MethodType<Value>::b, MethodType<Value>::c, algebra)
135  {
136  }
137 
138 public:
140 };
141 
142 template <size_t HistSize, class TRKType>
144  odeint::adams_bashforth<HistSize, typename TRKType::state_type, typename TRKType::value_type,
145  typename TRKType::deriv_type, typename TRKType::time_type, typename TRKType::algebra_type,
146  typename TRKType::operations_type, typename TRKType::resizer_type, TRKType>;
147 }
148 
149 #endif // DISCRETIZATION_OPTIONS_HPP
explicit_generic_rk_impl(const algebra_type &algebra=algebra_type())
static constexpr const boost::array< TValue, 3 > a3
static constexpr const boost::array< TValue, stageNr > b
Generic tree-like recursive structure that allows sub-structure access as well as ordered (array-like...
Definition: state.h:135
static constexpr const boost::array< TValue, 2 > a2
static constexpr const size_t stageNr
static constexpr const boost::array< TValue, stageNr > c
static constexpr const boost::array< TValue, 1 > a1
odeint::explicit_generic_rk< MethodType< Value >::stageNr, MethodType< Value >::stageNr, State, Value, Deriv, Time, Algebra, Operations, Resizer > stepper_base_type
odeint::adams_bashforth< HistSize, typename TRKType::state_type, typename TRKType::value_type, typename TRKType::deriv_type, typename TRKType::time_type, typename TRKType::algebra_type, typename TRKType::operations_type, typename TRKType::resizer_type, TRKType > explicit_adams_bashforth


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