Go to the documentation of this file.
25 #ifndef SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
26 #define SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
50 class SerialIntegratorSystem :
public SystemDynamicsInterface
59 Ptr getInstance()
const override {
return std::make_shared<SerialIntegratorSystem>(); }
64 bool isLinear()
const override {
return true; }
75 assert(
x.rows() == f.rows() &&
"SerialIntegratorSystem::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
77 const int num_integrator_states =
_dimension - 1;
79 if (
_dimension > 1) f.head(num_integrator_states) =
x.segment(1, num_integrator_states);
95 #ifdef MESSAGE_SUPPORT
97 void toMessage(messages::SystemDynamics& message)
const override
99 SystemDynamicsInterface::toMessage(message);
101 message.mutable_serial_integrators()->set_dimension(
_dimension);
102 message.mutable_serial_integrators()->set_time_constant(
_time_constant);
105 void fromMessage(
const messages::SystemDynamics& message, std::stringstream* issues)
override
107 SystemDynamicsInterface::fromMessage(message, issues);
109 _dimension = message.serial_integrators().dimension();
129 Ptr getInstance()
const override {
return std::make_shared<ParallelIntegratorSystem>(); }
134 bool isLinear()
const override {
return true; }
145 assert(
x.rows() == f.rows() &&
"ParallelIntegratorSystem::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
161 #ifdef MESSAGE_SUPPORT
163 void toMessage(messages::SystemDynamics& message)
const override
165 SystemDynamicsInterface::toMessage(message);
167 message.mutable_parallel_integrators()->set_dimension(
_dimension);
168 message.mutable_parallel_integrators()->set_time_constant(
_time_constant);
171 void fromMessage(
const messages::SystemDynamics& message, std::stringstream* issues)
override
173 SystemDynamicsInterface::fromMessage(message, issues);
193 Ptr getInstance()
const override {
return std::make_shared<LinearStateSpaceModel>(); }
198 bool isLinear()
const override {
return true; }
210 assert(
x.size() == f.size() &&
"LinearStateSpaceModel::dynamics(): x and f are not of the same size, do not forget to pre-allocate f.");
224 #ifdef MESSAGE_SUPPORT
226 void toMessage(messages::SystemDynamics& message)
const override
228 SystemDynamicsInterface::toMessage(message);
230 messages::LinearStateSpaceModel* msg = message.mutable_linear_state_space();
233 msg->mutable_a()->Resize(
_A.size(), 0);
237 msg->mutable_b()->Resize(
_B.size(), 0);
241 void fromMessage(
const messages::SystemDynamics& message, std::stringstream* issues)
override
243 SystemDynamicsInterface::fromMessage(message, issues);
245 const messages::LinearStateSpaceModel& msg = message.linear_state_space();
247 if (msg.a_size() == 0 || msg.b_size() == 0)
249 *issues <<
"LinearStateSpaceModel: Please specify a proper system matrix A and input matrix B.\n";
254 int numel_a = msg.a_size();
257 *issues <<
"LinearStateSpaceModel: system matrix A is not square.\n";
264 int numel_b = msg.b_size();
266 double q = numel_b / p;
267 if (p *
q != numel_b)
269 *issues <<
"LinearStateSpaceModel: input matrix B is not a valid matrix (number of columns must be " << p <<
").\n";
277 Eigen::MatrixXd
_A = Eigen::MatrixXd::Zero(1, 1);
278 Eigen::MatrixXd
_B = Eigen::MatrixXd::Zero(1, 1);
298 class DoubleIntegratorDiscreteTime :
public SystemDynamicsInterface
305 Ptr getInstance()
const override {
return std::make_shared<DoubleIntegratorDiscreteTime>(); }
310 bool isLinear()
const override {
return true; }
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.");
328 const double&
getDt()
const {
return _dt; }
332 #ifdef MESSAGE_SUPPORT
334 void toMessage(messages::SystemDynamics& message)
const override
336 SystemDynamicsInterface::toMessage(message);
337 message.mutable_double_integrator_discrete_time()->set_dt(
_dt);
340 void fromMessage(
const messages::SystemDynamics& message, std::stringstream* issue)
override
342 SystemDynamicsInterface::fromMessage(message, issue);
343 _dt = message.double_integrator_discrete_time().dt();
354 #endif // SRC_SYSTEMS_INCLUDE_CORBO_SYSTEMS_BENCHMARK_LINEAR_BENCHMARK_SYSTEMS_H_
const EIGEN_DEVICE_FUNC SqrtReturnType sqrt() const
Interface class for system dynamic equations.
System dynamics for a series of integrators (continuous-time)
const int & getDimension() const
Get current integrator chain dimension / order of the system.
int getStateDimension() const override
Return state dimension (x)
bool isLinear() const override
Check if the system dynamics are linear.
ParallelIntegratorSystem()
Default constructor (do not forget to set the dimension)
#define FACTORY_REGISTER_SYSTEM_DYNAMICS(type)
int getStateDimension() const override
Return state dimension (x)
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.
int getInputDimension() const override
Return the plant input dimension (u)
void setDimension(int dim)
Set integrator dimension (p >= 1)
int getInputDimension() const override
Return the plant input dimension (u)
bool isLinear() const override
Check if the system dynamics are linear.
const double & getTimeConstant() const
Get time constant T of the integrator.
void setParameters(const Eigen::Ref< const Eigen::MatrixXd > &A, const Eigen::Ref< const Eigen::MatrixXd > &B)
Set Time constant T of the integrator.
int getStateDimension() const override
Return state dimension (x)
SerialIntegratorSystem()
Default constructor (do not forget to set the dimension)
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
bool isLinear() const override
Check if the system dynamics are linear.
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
bool is_square(const Eigen::MatrixBase< Derived > &matrix)
Determine if a given matrix is square.
MatrixType B(b, *n, *nrhs, *ldb)
EIGEN_DEVICE_FUNC const Scalar & q
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
void setTimeConstant(double time_constant)
Set Time constant T of the integrator.
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
int getStateDimension() const override
Return state dimension (x)
int getInputDimension() const override
Return the plant input dimension (u)
System dynamics for a second order integrator (discrete-time)
const int & getDimension() const
Get current integrator chain dimension / order of the system.
std::shared_ptr< SystemDynamicsInterface > Ptr
A matrix or vector expression mapping an existing array of data.
DoubleIntegratorDiscreteTime()
Default constructor.
A matrix or vector expression mapping an existing expression.
LinearStateSpaceModel()
Default constructor (do not forget to set the dimension)
void setTimeConstant(double time_constant)
Set Time constant T of the integrator.
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
bool isContinuousTime() const override
Check if the system dynamics are defined in continuous-time.
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.
int getInputDimension() const override
Return the plant input dimension (u)
void setDt(double dt)
Set sampling time dt.
The matrix class, also used for vectors and row-vectors.
MatrixType A(a, *n, *n, *lda)
bool isLinear() const override
Check if the system dynamics are linear.
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
const double & getDt() const
Get current sampling time dt.
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.
const double & getTimeConstant() const
Get time constant T of the integrator.
void setDimension(int dim)
Set integrator dimension (p >= 1)
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.
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:52