step_response_generator.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_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_STEP_RESPONSE_GENERATOR_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_STEP_RESPONSE_GENERATOR_H_
27 
29 #include <memory>
30 
31 namespace corbo {
32 
47 class StepResponseGenerator : public ControllerInterface
48 {
49  public:
50  StepResponseGenerator() = default;
51 
52  // implements interface method
53  int getControlInputDimension() const override { return _u.size(); }
54  // implements interface method
55  int getStateDimension() const override { return _state_dim; }
56  // implements interface method
57  bool hasPiecewiseConstantControls() const override { return true; }
58  // implements interface method
59  bool providesFutureControls() const override { return false; }
60  // implements interface method
61  bool providesFutureStates() const override { return false; }
62 
63  // implements interface method
64  Ptr getInstance() const override { return std::make_shared<StepResponseGenerator>(); }
66  static Ptr getInstanceStatic() { return std::make_shared<StepResponseGenerator>(); }
67 
68  void setControl(const Eigen::VectorXd& u_step) { _u = u_step; }
69  const Eigen::VectorXd& getControl() const { return _u; }
70  void setStateDimension(int state_dim) { _state_dim = state_dim; }
71 
72  // implements interface method
73  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
74  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
75  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
76  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override
77  {
78  if (!u_sequence) return false;
79  u_sequence->clear();
80  u_sequence->add(0.0, _u);
81  return true;
82  }
83 
84  // implements interface method
85  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override {}
86 
87 #ifdef MESSAGE_SUPPORT
88  void toMessage(messages::StepResponseGenerator& message) const
89  {
90  message.set_state_dim(_state_dim);
91  message.mutable_u_step()->Resize(_u.size(), 0);
92  Eigen::Map<Eigen::VectorXd>(message.mutable_u_step()->mutable_data(), _u.size()) = _u;
93  }
94  void fromMessage(const messages::StepResponseGenerator& message, std::stringstream* issues = nullptr)
95  {
96  _state_dim = message.state_dim();
97  if (message.u_step_size() > 0)
98  _u = Eigen::Map<const Eigen::VectorXd>(message.u_step().data(), message.u_step_size());
99  else
100  _u.resize(0);
101  }
102 
103  // implements interface method
104  void toMessage(messages::Controller& message) const override { toMessage(*message.mutable_step_response_generator()); }
105  // implements interface method
106  void fromMessage(const messages::Controller& message, std::stringstream* issues = nullptr) override
107  {
108  fromMessage(message.step_response_generator(), issues);
109  }
110 #endif
111 
112  // implements interface method
113  void reset() override {}
114 
115  private:
116  Eigen::VectorXd _u;
117  int _state_dim = 0;
118 };
119 
121 
122 } // namespace corbo
123 
124 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_STEP_RESPONSE_GENERATOR_H_
corbo::StepResponseGenerator::getInstanceStatic
static Ptr getInstanceStatic()
Return a newly created shared instance of the implemented class (static method)
Definition: step_response_generator.h:110
corbo::StepResponseGenerator
Step Response Generator.
Definition: step_response_generator.h:69
corbo::StepResponseGenerator::_state_dim
int _state_dim
Definition: step_response_generator.h:161
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::StepResponseGenerator::setControl
void setControl(const Eigen::VectorXd &u_step)
Definition: step_response_generator.h:112
corbo::StepResponseGenerator::getInstance
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: step_response_generator.h:108
corbo::StepResponseGenerator::getStateDimension
int getStateDimension() const override
Return the dimension of the required plant state/output.
Definition: step_response_generator.h:99
controller_interface.h
corbo::StepResponseGenerator::_u
Eigen::VectorXd _u
Definition: step_response_generator.h:160
corbo::StepResponseGenerator::reset
void reset() override
Reset internal controller state and caches.
Definition: step_response_generator.h:157
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::StepResponseGenerator::getControlInputDimension
int getControlInputDimension() const override
Return the control input dimension.
Definition: step_response_generator.h:97
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
Definition: controller_interface.h:105
corbo::StepResponseGenerator::providesFutureControls
bool providesFutureControls() const override
Definition: step_response_generator.h:103
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
corbo::StepResponseGenerator::getAvailableSignals
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Definition: step_response_generator.h:129
corbo::StepResponseGenerator::StepResponseGenerator
StepResponseGenerator()=default
corbo::StepResponseGenerator::getControl
const Eigen::VectorXd & getControl() const
Definition: step_response_generator.h:113
corbo::StepResponseGenerator::step
bool step(const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, const Duration &dt, const Time &t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *sref=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="") override
Definition: step_response_generator.h:117
corbo::StepResponseGenerator::providesFutureStates
bool providesFutureStates() const override
Definition: step_response_generator.h:105
corbo::ControllerInterface::StateVector
Eigen::VectorXd StateVector
Definition: controller_interface.h:107
corbo::StepResponseGenerator::hasPiecewiseConstantControls
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
Definition: step_response_generator.h:101
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::StepResponseGenerator::setStateDimension
void setStateDimension(int state_dim)
Definition: step_response_generator.h:114
FACTORY_REGISTER_CONTROLLER
#define FACTORY_REGISTER_CONTROLLER(type)
Definition: controller_interface.h:189


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