linear_benchmark_systems.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
27 
29 
31 
32 namespace corbo {
33 
50 class SerialIntegratorSystem : public SystemDynamicsInterface
51 {
52  public:
56  explicit SerialIntegratorSystem(int dimension) : _dimension(dimension) {}
57 
58  // implements interface method
59  Ptr getInstance() const override { return std::make_shared<SerialIntegratorSystem>(); }
60 
61  // implements interface method
62  bool isContinuousTime() const override { return true; }
63  // implements interface method
64  bool isLinear() const override { return true; }
65 
66  // implements interface method
67  int getInputDimension() const override { return 1; }
68  // implements interface method
69  int getStateDimension() const override { return _dimension; }
70 
71  // implements interface method
73  {
74  assert(x.rows() == _dimension);
75  assert(x.rows() == f.rows() && "SerialIntegratorSystem::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
76 
77  const int num_integrator_states = _dimension - 1;
78 
79  if (_dimension > 1) f.head(num_integrator_states) = x.segment(1, num_integrator_states); // x^(1:n-1) = x^(2:n)
80  // add last equation containing control u
81  f[num_integrator_states] = u[0] / _time_constant; // x^(n) = u / T
82  }
83 
84  // access parameters
85 
87  const int& getDimension() const { return _dimension; }
89  void setDimension(int dim) { _dimension = dim; }
91  const double& getTimeConstant() const { return _time_constant; }
93  void setTimeConstant(double time_constant) { _time_constant = time_constant; }
94 
95 #ifdef MESSAGE_SUPPORT
96  // implements interface method
97  void toMessage(messages::SystemDynamics& message) const override
98  {
99  SystemDynamicsInterface::toMessage(message);
100 
101  message.mutable_serial_integrators()->set_dimension(_dimension);
102  message.mutable_serial_integrators()->set_time_constant(_time_constant);
103  }
104  // implements interface method
105  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
106  {
107  SystemDynamicsInterface::fromMessage(message, issues);
108 
109  _dimension = message.serial_integrators().dimension();
110  _time_constant = message.serial_integrators().time_constant();
111  }
112 #endif
113 
114  private:
115  int _dimension = 1;
116  double _time_constant = 1.0;
117 };
119 
121 {
122  public:
126  explicit ParallelIntegratorSystem(int dimension) : _dimension(dimension) {}
127 
128  // implements interface method
129  Ptr getInstance() const override { return std::make_shared<ParallelIntegratorSystem>(); }
130 
131  // implements interface method
132  bool isContinuousTime() const override { return true; }
133  // implements interface method
134  bool isLinear() const override { return true; }
135 
136  // implements interface method
137  int getInputDimension() const override { return _dimension; }
138  // implements interface method
139  int getStateDimension() const override { return _dimension; }
140 
141  // implements interface method
143  {
144  assert(x.rows() == _dimension);
145  assert(x.rows() == f.rows() && "ParallelIntegratorSystem::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
146 
147  f = _time_constant * u;
148  }
149 
150  // access parameters
151 
153  const int& getDimension() const { return _dimension; }
155  void setDimension(int dim) { _dimension = dim; }
157  const double& getTimeConstant() const { return _time_constant; }
159  void setTimeConstant(double time_constant) { _time_constant = time_constant; }
160 
161 #ifdef MESSAGE_SUPPORT
162  // implements interface method
163  void toMessage(messages::SystemDynamics& message) const override
164  {
165  SystemDynamicsInterface::toMessage(message);
166 
167  message.mutable_parallel_integrators()->set_dimension(_dimension);
168  message.mutable_parallel_integrators()->set_time_constant(_time_constant);
169  }
170  // implements interface method
171  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
172  {
173  SystemDynamicsInterface::fromMessage(message, issues);
174 
175  _dimension = message.parallel_integrators().dimension();
176  _time_constant = message.parallel_integrators().time_constant();
177  }
178 #endif
179 
180  private:
181  int _dimension = 1;
182  double _time_constant = 1.0;
183 };
185 
187 {
188  public:
191 
192  // implements interface method
193  Ptr getInstance() const override { return std::make_shared<LinearStateSpaceModel>(); }
194 
195  // implements interface method
196  bool isContinuousTime() const override { return true; }
197  // implements interface method
198  bool isLinear() const override { return true; }
199 
200  // implements interface method
201  int getInputDimension() const override { return _B.cols(); }
202  // implements interface method
203  int getStateDimension() const override { return _A.rows(); }
204 
205  // implements interface method
207  {
208  assert(x.size() == getStateDimension());
209  assert(u.size() == getInputDimension());
210  assert(x.size() == f.size() && "LinearStateSpaceModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
211 
212  f = _A * x + _B * u;
213  }
214 
215  // access parameters
216 
219  {
220  _A = A;
221  _B = B;
222  }
223 
224 #ifdef MESSAGE_SUPPORT
225  // implements interface method
226  void toMessage(messages::SystemDynamics& message) const override
227  {
228  SystemDynamicsInterface::toMessage(message);
229 
230  messages::LinearStateSpaceModel* msg = message.mutable_linear_state_space();
231 
232  // A
233  msg->mutable_a()->Resize(_A.size(), 0);
234  Eigen::Map<Eigen::VectorXd>(msg->mutable_a()->mutable_data(), _A.size()) = _A;
235 
236  // B
237  msg->mutable_b()->Resize(_B.size(), 0);
238  Eigen::Map<Eigen::VectorXd>(msg->mutable_b()->mutable_data(), _B.size()) = _B;
239  }
240  // implements interface method
241  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
242  {
243  SystemDynamicsInterface::fromMessage(message, issues);
244 
245  const messages::LinearStateSpaceModel& msg = message.linear_state_space();
246 
247  if (msg.a_size() == 0 || msg.b_size() == 0)
248  {
249  *issues << "LinearStateSpaceModel: Please specify a proper system matrix A and input matrix B.\n";
250  return;
251  }
252 
253  // A
254  int numel_a = msg.a_size();
255  if (!is_square(numel_a))
256  {
257  *issues << "LinearStateSpaceModel: system matrix A is not square.\n";
258  return;
259  }
260  int p = std::sqrt(numel_a);
261  _A = Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(msg.a().data(), p, p);
262 
263  // B
264  int numel_b = msg.b_size();
265 
266  double q = numel_b / p;
267  if (p * q != numel_b)
268  {
269  *issues << "LinearStateSpaceModel: input matrix B is not a valid matrix (number of columns must be " << p << ").\n";
270  return;
271  }
272  _B = Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(msg.b().data(), p, (int)q);
273  }
274 #endif
275 
276  private:
277  Eigen::MatrixXd _A = Eigen::MatrixXd::Zero(1, 1);
278  Eigen::MatrixXd _B = Eigen::MatrixXd::Zero(1, 1);
279 };
280 FACTORY_REGISTER_SYSTEM_DYNAMICS(LinearStateSpaceModel)
281 
282 
298 class DoubleIntegratorDiscreteTime : public SystemDynamicsInterface
299 {
300  public:
303 
304  // implements interface method
305  Ptr getInstance() const override { return std::make_shared<DoubleIntegratorDiscreteTime>(); }
306 
307  // implements interface method
308  bool isContinuousTime() const override { return false; }
309  // implements interface method
310  bool isLinear() const override { return true; }
311 
312  // implements interface method
313  int getInputDimension() const override { return 1; }
314  // implements interface method
315  int getStateDimension() const override { return 2; }
316 
317  // implements interface method
319  {
320  assert(x.rows() == 2);
321  assert(x.rows() == f.rows() && "IntegratorSystemCont::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
322 
323  f[0] = x[0] + _dt * x[1] + 0.5 * _dt * _dt * u[0];
324  f[1] = x[1] + _dt * u[0];
325  }
326 
328  const double& getDt() const { return _dt; }
330  void setDt(double dt) { _dt = dt; }
331 
332 #ifdef MESSAGE_SUPPORT
333  // implements interface method
334  void toMessage(messages::SystemDynamics& message) const override
335  {
336  SystemDynamicsInterface::toMessage(message);
337  message.mutable_double_integrator_discrete_time()->set_dt(_dt);
338  }
339  // implements interface method
340  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issue) override
341  {
342  SystemDynamicsInterface::fromMessage(message, issue);
343  _dt = message.double_integrator_discrete_time().dt();
344  }
345 #endif
346 
347  private:
348  double _dt = 1.0;
349 };
351 
352 } // namespace corbo
353 
354 #endif // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
sqrt
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Definition: ArrayCwiseUnaryOps.h:152
corbo::LinearStateSpaceModel::_A
Eigen::MatrixXd _A
Definition: linear_benchmark_systems.h:299
corbo::SystemDynamicsInterface
Interface class for system dynamic equations.
Definition: system_dynamics_interface.h:88
corbo::SerialIntegratorSystem
System dynamics for a series of integrators (continuous-time)
Definition: linear_benchmark_systems.h:72
corbo::DoubleIntegratorDiscreteTime::_dt
double _dt
Definition: linear_benchmark_systems.h:370
system_dynamics_interface.h
corbo::ParallelIntegratorSystem::getDimension
const int & getDimension() const
Get current integrator chain dimension / order of the system.
Definition: linear_benchmark_systems.h:175
corbo::SerialIntegratorSystem::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: linear_benchmark_systems.h:113
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::LinearStateSpaceModel::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: linear_benchmark_systems.h:220
corbo::ParallelIntegratorSystem::ParallelIntegratorSystem
ParallelIntegratorSystem()
Default constructor (do not forget to set the dimension)
Definition: linear_benchmark_systems.h:146
corbo::ParallelIntegratorSystem
Definition: linear_benchmark_systems.h:142
corbo::SerialIntegratorSystem::_dimension
int _dimension
Definition: linear_benchmark_systems.h:159
FACTORY_REGISTER_SYSTEM_DYNAMICS
#define FACTORY_REGISTER_SYSTEM_DYNAMICS(type)
Definition: system_dynamics_interface.h:202
corbo::LinearStateSpaceModel::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: linear_benchmark_systems.h:225
corbo::LinearStateSpaceModel::dynamics
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
Evaluate the system dynamics equation.
Definition: linear_benchmark_systems.h:228
corbo::SerialIntegratorSystem::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: linear_benchmark_systems.h:111
corbo::ParallelIntegratorSystem::setDimension
void setDimension(int dim)
Set integrator dimension (p >= 1)
Definition: linear_benchmark_systems.h:177
corbo::ParallelIntegratorSystem::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: linear_benchmark_systems.h:159
Eigen::RowMajor
@ RowMajor
Definition: Constants.h:322
corbo::SerialIntegratorSystem::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: linear_benchmark_systems.h:108
corbo::ParallelIntegratorSystem::getTimeConstant
const double & getTimeConstant() const
Get time constant T of the integrator.
Definition: linear_benchmark_systems.h:179
corbo::LinearStateSpaceModel::setParameters
void setParameters(const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B)
Set Time constant T of the integrator.
Definition: linear_benchmark_systems.h:240
corbo::DoubleIntegratorDiscreteTime::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: linear_benchmark_systems.h:337
corbo::SerialIntegratorSystem::SerialIntegratorSystem
SerialIntegratorSystem()
Default constructor (do not forget to set the dimension)
Definition: linear_benchmark_systems.h:98
corbo::SerialIntegratorSystem::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: linear_benchmark_systems.h:106
corbo::ParallelIntegratorSystem::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: linear_benchmark_systems.h:156
corbo::LinearStateSpaceModel::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: linear_benchmark_systems.h:218
corbo::is_square
bool is_square(const Eigen::MatrixBase< Derived > &matrix)
Determine if a given matrix is square.
Definition: matrix_utilities.h:65
B
MatrixType B(b, *n, *nrhs, *ldb)
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1520
corbo::DoubleIntegratorDiscreteTime::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: linear_benchmark_systems.h:327
corbo::SerialIntegratorSystem::setTimeConstant
void setTimeConstant(double time_constant)
Set Time constant T of the integrator.
Definition: linear_benchmark_systems.h:137
corbo::SerialIntegratorSystem::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: linear_benchmark_systems.h:103
corbo::LinearStateSpaceModel::_B
Eigen::MatrixXd _B
Definition: linear_benchmark_systems.h:300
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::ParallelIntegratorSystem::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: linear_benchmark_systems.h:161
matrix_utilities.h
corbo::DoubleIntegratorDiscreteTime::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: linear_benchmark_systems.h:335
corbo::DoubleIntegratorDiscreteTime
System dynamics for a second order integrator (discrete-time)
Definition: linear_benchmark_systems.h:320
corbo::SerialIntegratorSystem::getDimension
const int & getDimension() const
Get current integrator chain dimension / order of the system.
Definition: linear_benchmark_systems.h:131
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
corbo::DoubleIntegratorDiscreteTime::DoubleIntegratorDiscreteTime
DoubleIntegratorDiscreteTime()
Default constructor.
Definition: linear_benchmark_systems.h:324
corbo::LinearStateSpaceModel
Definition: linear_benchmark_systems.h:208
int
return int(ret)+1
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::LinearStateSpaceModel::LinearStateSpaceModel
LinearStateSpaceModel()
Default constructor (do not forget to set the dimension)
Definition: linear_benchmark_systems.h:212
corbo::ParallelIntegratorSystem::setTimeConstant
void setTimeConstant(double time_constant)
Set Time constant T of the integrator.
Definition: linear_benchmark_systems.h:181
corbo::ParallelIntegratorSystem::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: linear_benchmark_systems.h:154
corbo::ParallelIntegratorSystem::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: linear_benchmark_systems.h:151
corbo::ParallelIntegratorSystem::_time_constant
double _time_constant
Definition: linear_benchmark_systems.h:204
corbo::DoubleIntegratorDiscreteTime::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: linear_benchmark_systems.h:330
corbo::DoubleIntegratorDiscreteTime::dynamics
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
Evaluate the system dynamics equation.
Definition: linear_benchmark_systems.h:340
corbo::LinearStateSpaceModel::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: linear_benchmark_systems.h:223
corbo::DoubleIntegratorDiscreteTime::setDt
void setDt(double dt)
Set sampling time dt.
Definition: linear_benchmark_systems.h:352
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
A
MatrixType A(a, *n, *n, *lda)
corbo::SerialIntegratorSystem::_time_constant
double _time_constant
Definition: linear_benchmark_systems.h:160
corbo::DoubleIntegratorDiscreteTime::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: linear_benchmark_systems.h:332
corbo::LinearStateSpaceModel::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: linear_benchmark_systems.h:215
corbo::DoubleIntegratorDiscreteTime::getDt
const double & getDt() const
Get current sampling time dt.
Definition: linear_benchmark_systems.h:350
corbo::SerialIntegratorSystem::dynamics
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
Evaluate the system dynamics equation.
Definition: linear_benchmark_systems.h:116
corbo::SerialIntegratorSystem::getTimeConstant
const double & getTimeConstant() const
Get time constant T of the integrator.
Definition: linear_benchmark_systems.h:135
corbo::SerialIntegratorSystem::setDimension
void setDimension(int dim)
Set integrator dimension (p >= 1)
Definition: linear_benchmark_systems.h:133
corbo::ParallelIntegratorSystem::_dimension
int _dimension
Definition: linear_benchmark_systems.h:203
corbo::ParallelIntegratorSystem::dynamics
void dynamics(const Eigen::Ref< const StateVector > &x, const Eigen::Ref< const ControlVector > &u, Eigen::Ref< StateVector > f) const override
Evaluate the system dynamics equation.
Definition: linear_benchmark_systems.h:164


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:52