nonlinear_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_NONLINEAR_BENCHMARK_SYSTEMS_H_
26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_NONLINEAR_BENCHMARK_SYSTEMS_H_
27 
29 
30 namespace corbo {
31 
32 class VanDerPolOscillator : public SystemDynamicsInterface
33 {
34  public:
37 
38  // implements interface method
39  Ptr getInstance() const override { return std::make_shared<VanDerPolOscillator>(); }
40 
41  // implements interface method
42  bool isContinuousTime() const override { return true; }
43  // implements interface method
44  bool isLinear() const override { return false; }
45 
46  // implements interface method
47  int getInputDimension() const override { return 1; }
48  // implements interface method
49  int getStateDimension() const override { return 2; }
50 
51  // implements interface method
53  {
54  assert(x.size() == getStateDimension());
55  assert(u.size() == getInputDimension());
56  assert(x.size() == f.size() && "VanDerPolOscillator::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
57 
58  f[0] = x[1]; // xdot = xdot
59  f[1] = -_a * (x[0] * x[0] - 1) * x[1] - x[0] + u[0];
60  }
61 
62  // access parameters
63  const double& getDampingCoefficient() const { return _a; }
64  void setDampingCoefficient(double a) { _a = a; }
65 
66 #ifdef MESSAGE_SUPPORT
67  // implements interface method
68  void toMessage(messages::SystemDynamics& message) const override
69  {
70  SystemDynamicsInterface::toMessage(message);
71 
72  message.mutable_van_der_pol_oscillator()->set_a(_a);
73  }
74  // implements interface method
75  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
76  {
77  SystemDynamicsInterface::fromMessage(message, issues);
78 
79  _a = message.van_der_pol_oscillator().a();
80  }
81 #endif
82 
83  private:
84  double _a = 1;
85 };
87 
89 {
90  public:
93 
94  // implements interface method
95  Ptr getInstance() const override { return std::make_shared<DuffingOscillator>(); }
96 
97  // implements interface method
98  bool isContinuousTime() const override { return true; }
99  // implements interface method
100  bool isLinear() const override { return false; }
101 
102  // implements interface method
103  int getInputDimension() const override { return 1; }
104  // implements interface method
105  int getStateDimension() const override { return 2; }
106 
107  // implements interface method
109  {
110  assert(x.size() == getStateDimension());
111  assert(u.size() == getInputDimension());
112  assert(x.size() == f.size() && "DuffingOscillator::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
113 
114  f[0] = x[1]; // xdot = xdot
115  f[1] = -_damping * x[1] - _spring_alpha * x[0] - _spring_beta * x[0] * x[0] * x[0] + u[0];
116  }
117 
118  // access parameters
119  void setParameters(double damping, double spring_alpha, double spring_beta)
120  {
121  _damping = damping;
122  _spring_alpha = spring_alpha;
123  _spring_beta = spring_beta;
124  }
125 
126 #ifdef MESSAGE_SUPPORT
127  // implements interface method
128  void toMessage(messages::SystemDynamics& message) const override
129  {
130  SystemDynamicsInterface::toMessage(message);
131 
132  message.mutable_duffing_oscillator()->set_damping(_damping);
133  message.mutable_duffing_oscillator()->set_spring_alpha(_spring_alpha);
134  message.mutable_duffing_oscillator()->set_spring_beta(_spring_beta);
135  }
136  // implements interface method
137  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
138  {
139  SystemDynamicsInterface::fromMessage(message, issues);
140 
141  _damping = message.duffing_oscillator().damping();
142  _spring_alpha = message.duffing_oscillator().spring_alpha();
143  _spring_beta = message.duffing_oscillator().spring_beta();
144  }
145 #endif
146 
147  private:
148  double _damping = 1;
149  double _spring_alpha = 1;
150  double _spring_beta = 1;
151 };
152 FACTORY_REGISTER_SYSTEM_DYNAMICS(DuffingOscillator)
153 
154 class FreeSpaceRocket : public SystemDynamicsInterface
155 {
156  public:
158  FreeSpaceRocket() {}
159 
160  // implements interface method
161  Ptr getInstance() const override { return std::make_shared<FreeSpaceRocket>(); }
162 
163  // implements interface method
164  bool isContinuousTime() const override { return true; }
165  // implements interface method
166  bool isLinear() const override { return false; }
167 
168  // implements interface method
169  int getInputDimension() const override { return 1; }
170  // implements interface method
171  int getStateDimension() const override { return 3; }
172 
173  // implements interface method
175  {
176  assert(x.size() == getStateDimension());
177  assert(u.size() == getInputDimension());
178  assert(x.size() == f.size() && "FreeSpaceRocket::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
179 
180  f[0] = x[1]; // sdot = v
181  f[1] = (u[0] - 0.02 * x[1] * x[1]) / x[2]; // (u-0.02*v^2)/m
182  f[2] = -0.01 * u[0] * u[0]; // -0.01 * u^2
183  }
184 };
185 FACTORY_REGISTER_SYSTEM_DYNAMICS(FreeSpaceRocket)
186 
188 {
189  public:
192 
193  // implements interface method
194  Ptr getInstance() const override { return std::make_shared<SimplePendulum>(); }
195 
196  // implements interface method
197  bool isContinuousTime() const override { return true; }
198  // implements interface method
199  bool isLinear() const override { return false; }
200 
201  // implements interface method
202  int getInputDimension() const override { return 1; }
203  // implements interface method
204  int getStateDimension() const override { return 2; }
205 
206  // implements interface method
207  void dynamics(const Eigen::Ref<const StateVector>& x, const Eigen::Ref<const ControlVector>& u, Eigen::Ref<StateVector> f) const override
208  {
209  assert(u.size() == getInputDimension());
210  assert(x.size() == getStateDimension());
211  assert(x.size() == f.size() && "SimplePendulum::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
212 
213  f[0] = x[1]; // phidot = phidot
214  f[1] = u[0] - _rho / (_m * _l * _l) * x[1] - _g / _l * std::sin(x[0]);
215  }
216 
217  // access parameters
218  void setParameters(double mass, double length, double gravitation, double friction)
219  {
220  _m = mass;
221  _l = length;
222  _g = gravitation;
223  _rho = friction;
224  }
225 
226 #ifdef MESSAGE_SUPPORT
227  // implements interface method
228  void toMessage(messages::SystemDynamics& message) const override
229  {
230  SystemDynamicsInterface::toMessage(message);
231 
232  messages::SimplePendulum* msg = message.mutable_simple_pendulum();
233 
234  msg->set_m(_m);
235  msg->set_l(_l);
236  msg->set_g(_g);
237  msg->set_rho(_rho);
238  }
239  // implements interface method
240  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
241  {
242  SystemDynamicsInterface::fromMessage(message, issues);
243 
244  const messages::SimplePendulum& msg = message.simple_pendulum();
245 
246  _m = msg.m();
247  _l = msg.l();
248  _g = msg.g();
249  _rho = msg.rho();
250  }
251 #endif
252 
253  private:
254  double _m = 0.205;
255  double _l = 0.34;
256  double _g = 9.81;
257  double _rho = 0;
258 };
259 FACTORY_REGISTER_SYSTEM_DYNAMICS(SimplePendulum)
260 
261 class MasslessPendulum : public SystemDynamicsInterface
262 {
263  public:
265  MasslessPendulum() {}
266 
267  // implements interface method
268  Ptr getInstance() const override { return std::make_shared<MasslessPendulum>(); }
269 
270  // implements interface method
271  bool isContinuousTime() const override { return true; }
272  // implements interface method
273  bool isLinear() const override { return false; }
274 
275  // implements interface method
276  int getInputDimension() const override { return 1; }
277  // implements interface method
278  int getStateDimension() const override { return 2; }
279 
280  // implements interface method
282  {
283  assert(u.size() == getInputDimension());
284  assert(x.size() == getStateDimension());
285  assert(x.size() == f.size() && "MasslessPendulum::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
286 
287  f[0] = x[1]; // phidot = phidot
288  f[1] = u[0] - _omega0 * std::sin(x[0]);
289  }
290 
291  // access parameters
292  void setParameter(double omega0) { _omega0 = omega0; }
293 
294 #ifdef MESSAGE_SUPPORT
295  // implements interface method
296  void toMessage(messages::SystemDynamics& message) const override
297  {
298  SystemDynamicsInterface::toMessage(message);
299  messages::MasslessPendulum* msg = message.mutable_massless_pendulum();
300  msg->set_omega0(_omega0);
301  }
302  // implements interface method
303  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
304  {
305  SystemDynamicsInterface::fromMessage(message, issues);
306 
307  const messages::MasslessPendulum& msg = message.massless_pendulum();
308  _omega0 = msg.omega0();
309  }
310 #endif
311 
312  private:
313  double _omega0 = 1.0;
314 };
316 
317 class CartPole : public SystemDynamicsInterface
318 {
319  public:
321  CartPole() {}
322 
323  // implements interface method
324  Ptr getInstance() const override { return std::make_shared<CartPole>(); }
325 
326  // implements interface method
327  bool isContinuousTime() const override { return true; }
328  // implements interface method
329  bool isLinear() const override { return false; }
330 
331  // implements interface method
332  int getInputDimension() const override { return 1; }
333  // implements interface method
334  int getStateDimension() const override { return 4; }
335 
336  // implements interface method
338  {
339  assert(u.size() == getInputDimension());
340  assert(x.size() == getStateDimension());
341  assert(x.size() == f.size() && "CartPoleSystem::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
342 
343  // [x phi xdot phidot]
344 
345  double sin_phi_phidot_sq = std::sin(x[1]) * x[3] * x[3];
346  double denum = _mc + _mp * (1 - std::pow(std::cos(x[1]), 2));
347 
348  f[0] = x[2]; // xdot = xdot
349  f[1] = x[3]; // phidot = phidot
350  f[2] = (_l * _mp * sin_phi_phidot_sq + u[0] + _mp * _g * std::cos(x[1]) * std::sin(x[1])) / denum;
351  f[3] = -(_l * _mp * std::cos(x[1]) * sin_phi_phidot_sq + u[0] * std::cos(x[1]) + (_mp + _mc) * _g * std::sin(x[1])) / (_l * denum);
352  }
353 
354 // access parameters
355 // void setParameters(double mass, double length, double gravitation, double friction)
356 // {
357 // _m = mass;
358 // _l = length;
359 // _g = gravitation;
360 // _rho = friction;
361 // }
362 
363 #ifdef MESSAGE_SUPPORT
364  // implements interface method
365  void toMessage(messages::SystemDynamics& message) const override
366  {
367  SystemDynamicsInterface::toMessage(message);
368 
369  messages::CartPole* msg = message.mutable_cart_pole();
370 
371  msg->set_mc(_mc);
372  msg->set_mp(_mp);
373  msg->set_l(_l);
374  msg->set_g(_g);
375  }
376  // implements interface method
377  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
378  {
379  SystemDynamicsInterface::fromMessage(message, issues);
380 
381  const messages::CartPole& msg = message.cart_pole();
382 
383  _mc = msg.mc();
384  _mp = msg.mp();
385  _l = msg.l();
386  _g = msg.g();
387  }
388 #endif
389 
390  private:
391  double _mc = 1.0;
392  double _mp = 0.3;
393  double _l = 0.5;
394  double _g = 9.81;
395 
396  // suggested u_max: 20N
397  // x_max = 2 m
398 };
400 
401 // Taken from:
402 // Verschueren et al., "A Stabilizing Nonlinear Model Predictive Control Scheme for Time-optimal Point-to-point Motions", CDC, 2017.
403 // Chen and Allgoewer, "A quasi-infinite horizon nonlinear model predictive control scheme with guaranteed stability", Automatica, 2002.
404 // Recommended bounds: -10 < u < 10
405 // N = 50
406 class ToyExample : public SystemDynamicsInterface
407 {
408  public:
410  ToyExample() {}
411 
412  // implements interface method
413  Ptr getInstance() const override { return std::make_shared<ToyExample>(); }
414 
415  // implements interface method
416  bool isContinuousTime() const override { return true; }
417  // implements interface method
418  bool isLinear() const override { return false; }
419 
420  // implements interface method
421  int getInputDimension() const override { return 1; }
422  // implements interface method
423  int getStateDimension() const override { return 2; }
424 
425  // implements interface method
427  {
428  assert(x.size() == getStateDimension());
429  assert(u.size() == getInputDimension());
430  assert(x.size() == f.size() && "ToyExample::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
431 
432  // x = [p; q]
433 
434  f[0] = x[1] + u[0] * (_mu + (1.0 - _mu) * x[0]); // pdot = q + u(mu + (1-mu)p)
435  f[1] = x[0] + u[0] * (_mu - 4.0 * (1.0 - _mu) * x[1]); // qdot = p + u(mu-4(1-mu)q)
436  }
437 
438  // access parameters
439  void setParameters(double mu) { _mu = mu; }
440 
441 #ifdef MESSAGE_SUPPORT
442  // implements interface method
443  void toMessage(messages::SystemDynamics& message) const override
444  {
445  SystemDynamicsInterface::toMessage(message);
446 
447  message.mutable_toy_example()->set_mu(_mu);
448  }
449  // implements interface method
450  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
451  {
452  SystemDynamicsInterface::fromMessage(message, issues);
453 
454  _mu = message.toy_example().mu();
455  }
456 #endif
457 
458  private:
459  double _mu = 0.5;
460 };
462 
464 {
465  public:
467  ArtsteinsCircle() {}
468 
469  // implements interface method
470  Ptr getInstance() const override { return std::make_shared<ArtsteinsCircle>(); }
471 
472  // implements interface method
473  bool isContinuousTime() const override { return true; }
474  // implements interface method
475  bool isLinear() const override { return false; }
476 
477  // implements interface method
478  int getInputDimension() const override { return 1; }
479  // implements interface method
480  int getStateDimension() const override { return 2; }
481 
482  // implements interface method
484  {
485  assert(x.size() == getStateDimension());
486  assert(u.size() == getInputDimension());
487  assert(x.size() == f.size() && "ArtsteinsCircle::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
488 
489  f[0] = (x[0] * x[0] - x[1] * x[1]) * u[0];
490  f[1] = 2 * x[0] * x[1] * u[0];
491  }
492 
493 #ifdef MESSAGE_SUPPORT
494  // implements interface method
495  void toMessage(messages::SystemDynamics& message) const override
496  {
497  SystemDynamicsInterface::toMessage(message);
498 
499  message.mutable_artsteins_circle();
500  }
501  // implements interface method
502  void fromMessage(const messages::SystemDynamics& message, std::stringstream* issues) override
503  {
504  SystemDynamicsInterface::fromMessage(message, issues);
505  }
506 #endif
507 };
508 FACTORY_REGISTER_SYSTEM_DYNAMICS(ArtsteinsCircle)
509 
510 } // namespace corbo
511 
512 #endif // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_NONLINEAR_BENCHMARK_SYSTEMS_H_
corbo::VanDerPolOscillator::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:83
corbo::CartPole
Definition: nonlinear_benchmark_systems.h:339
sin
const EIGEN_DEVICE_FUNC SinReturnType sin() const
Definition: ArrayCwiseUnaryOps.h:220
corbo::MasslessPendulum::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:290
corbo::SystemDynamicsInterface
Interface class for system dynamic equations.
Definition: system_dynamics_interface.h:88
corbo::ToyExample::ToyExample
ToyExample()
Default constructor.
Definition: nonlinear_benchmark_systems.h:432
system_dynamics_interface.h
corbo::VanDerPolOscillator::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:88
corbo::ToyExample::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:438
corbo::ArtsteinsCircle::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:492
corbo::MasslessPendulum
Definition: nonlinear_benchmark_systems.h:283
corbo::VanDerPolOscillator::VanDerPolOscillator
VanDerPolOscillator()
Default constructor.
Definition: nonlinear_benchmark_systems.h:80
Eigen::half_impl::pow
EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC half pow(const half &a, const half &b)
Definition: Half.h:477
corbo::ToyExample::_mu
double _mu
Definition: nonlinear_benchmark_systems.h:481
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::VanDerPolOscillator
Definition: nonlinear_benchmark_systems.h:54
corbo::MasslessPendulum::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:300
corbo::DuffingOscillator
Definition: nonlinear_benchmark_systems.h:110
corbo::MasslessPendulum::setParameter
void setParameter(double omega0)
Definition: nonlinear_benchmark_systems.h:314
FACTORY_REGISTER_SYSTEM_DYNAMICS
#define FACTORY_REGISTER_SYSTEM_DYNAMICS(type)
Definition: system_dynamics_interface.h:202
corbo::ToyExample::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:440
corbo::CartPole::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:349
corbo::ArtsteinsCircle::ArtsteinsCircle
ArtsteinsCircle()
Default constructor.
Definition: nonlinear_benchmark_systems.h:489
corbo::MasslessPendulum::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: nonlinear_benchmark_systems.h:303
corbo::FreeSpaceRocket::FreeSpaceRocket
FreeSpaceRocket()
Default constructor.
Definition: nonlinear_benchmark_systems.h:180
corbo::SimplePendulum
Definition: nonlinear_benchmark_systems.h:209
corbo::VanDerPolOscillator::setDampingCoefficient
void setDampingCoefficient(double a)
Definition: nonlinear_benchmark_systems.h:108
corbo::CartPole::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: nonlinear_benchmark_systems.h:359
corbo::FreeSpaceRocket::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:191
corbo::ToyExample
Definition: nonlinear_benchmark_systems.h:428
corbo::FreeSpaceRocket::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:183
corbo::FreeSpaceRocket::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:186
corbo::CartPole::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:356
corbo::FreeSpaceRocket::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: nonlinear_benchmark_systems.h:196
corbo::CartPole::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:351
corbo::FreeSpaceRocket::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:193
corbo::ArtsteinsCircle::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:502
corbo::ArtsteinsCircle::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: nonlinear_benchmark_systems.h:505
corbo::ArtsteinsCircle::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:500
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::CartPole::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:354
corbo::MasslessPendulum::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:295
corbo::SystemDynamicsInterface::Ptr
std::shared_ptr< SystemDynamicsInterface > Ptr
Definition: system_dynamics_interface.h:91
corbo::ToyExample::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:445
corbo::ToyExample::setParameters
void setParameters(double mu)
Definition: nonlinear_benchmark_systems.h:461
corbo::CartPole::_mc
double _mc
Definition: nonlinear_benchmark_systems.h:413
corbo::CartPole::_mp
double _mp
Definition: nonlinear_benchmark_systems.h:414
corbo::CartPole::CartPole
CartPole()
Default constructor.
Definition: nonlinear_benchmark_systems.h:343
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::VanDerPolOscillator::_a
double _a
Definition: nonlinear_benchmark_systems.h:128
corbo::VanDerPolOscillator::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:91
corbo::VanDerPolOscillator::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: nonlinear_benchmark_systems.h:96
a
Scalar * a
Definition: cholesky.cpp:26
corbo::MasslessPendulum::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:298
corbo::ArtsteinsCircle::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:495
corbo::ToyExample::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: nonlinear_benchmark_systems.h:448
corbo::CartPole::_l
double _l
Definition: nonlinear_benchmark_systems.h:415
corbo::FreeSpaceRocket::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:188
corbo::VanDerPolOscillator::getStateDimension
int getStateDimension() const override
Return state dimension (x)
Definition: nonlinear_benchmark_systems.h:93
corbo::MasslessPendulum::MasslessPendulum
MasslessPendulum()
Default constructor.
Definition: nonlinear_benchmark_systems.h:287
corbo::CartPole::_g
double _g
Definition: nonlinear_benchmark_systems.h:416
corbo::VanDerPolOscillator::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:86
corbo::MasslessPendulum::isContinuousTime
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Definition: nonlinear_benchmark_systems.h:293
corbo::ArtsteinsCircle::isLinear
bool isLinear() const override
Check if the system dynamics are linear.
Definition: nonlinear_benchmark_systems.h:497
corbo::ArtsteinsCircle
Definition: nonlinear_benchmark_systems.h:485
corbo::ToyExample::getInputDimension
int getInputDimension() const override
Return the plant input dimension (u)
Definition: nonlinear_benchmark_systems.h:443
corbo::MasslessPendulum::_omega0
double _omega0
Definition: nonlinear_benchmark_systems.h:335
corbo::CartPole::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:346
corbo::VanDerPolOscillator::getDampingCoefficient
const double & getDampingCoefficient() const
Definition: nonlinear_benchmark_systems.h:107
cos
const EIGEN_DEVICE_FUNC CosReturnType cos() const
Definition: ArrayCwiseUnaryOps.h:202
corbo::ToyExample::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: nonlinear_benchmark_systems.h:435


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