predictive_controller.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_PREDICTIVE_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_
27 
30 
31 #include <memory>
32 
33 namespace corbo {
34 
50 class PredictiveController : public ControllerInterface
51 {
52  public:
53  using Ptr = std::shared_ptr<PredictiveController>;
54 
56 
57  // implements interface method
58  int getControlInputDimension() const override { return _ocp ? _ocp->getControlInputDimension() : 0; }
59  // implements interface method
60  int getStateDimension() const override { return _ocp ? _ocp->getStateDimension() : 0; }
61  // implements interface method
62  bool hasPiecewiseConstantControls() const override { return _ocp ? _ocp->isConstantControlAction() : false; }
63  // implements interface method
64  bool providesFutureControls() const override { return _ocp ? _ocp->providesFutureControls() : false; }
65  // implements interface method
66  bool providesFutureStates() const override { return _ocp ? _ocp->providesFutureStates() : false; }
67 
68  // implements interface method
69  ControllerInterface::Ptr getInstance() const override { return std::make_shared<PredictiveController>(); }
70  static Ptr getInstanceStatic() { return std::make_shared<PredictiveController>(); }
71 
74 
75  // implements interface method
76  bool initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
77  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref = nullptr) override;
78 
79  // implements interface method
80  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
81  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
82  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
83  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override;
84 
85  // implements interface method
86  double getControlDuration() const override { return _ocp ? _ocp->getFirstDt() : 0.0; }
87 
88  // implements interface method
89  bool supportsAsynchronousControl() const override { return true; }
90 
91  // implements interface method
92  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override;
93 
94  // implements interface method
95  void reset() override;
96 
97  const int& getNumOcpIterations() const { return _num_ocp_iterations; }
98  void setNumOcpIterations(int ocp_iter) { _num_ocp_iterations = ocp_iter; }
99 
100  const bool& isPublishPrediction() const { return _publish_prediction; }
101  void setPublishPrediction(bool publish) { _publish_prediction = publish; }
102 
103  void setOutputControlSequenceLenght(bool activate) { _output_control_sequence = activate; }
104  void setOutputStateSequenceLenght(bool activate) { _output_state_sequence = activate; }
105 
108 
109  void sendSignals(double t, SignalTargetInterface& signal_target, const std::string& ns = "") const override;
110 
112  {
113  return std::make_shared<ControllerStatistics>(_statistics);
114  } // TODO(roesmann): make_shared?
115 
116 #ifdef MESSAGE_SUPPORT
117  void toMessage(corbo::messages::PredictiveController& message) const;
118  void fromMessage(const corbo::messages::PredictiveController& message, std::stringstream* issues = nullptr);
119 
120  // implements interface method
121  void toMessage(corbo::messages::Controller& message) const override { toMessage(*message.mutable_predictive_controller()); }
122  // implements interface method
123  void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) override
124  {
125  fromMessage(message.predictive_controller(), issues);
126  }
127 #endif
128 
129  protected:
133 
135 
136  bool _auto_update_prev_control = true;
137 
138  int _num_ocp_iterations = 1;
139  bool _publish_prediction = true;
140  // double _publish_prediction_dt = -1;
143 
144  bool _initialized = false;
145 };
146 
148 
149 } // namespace corbo
150 
151 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PREDICTIVE_CONTROLLER_H_
corbo::PredictiveController::_num_ocp_iterations
int _num_ocp_iterations
Definition: predictive_controller.h:182
corbo::PredictiveController::setPublishPrediction
void setPublishPrediction(bool publish)
Definition: predictive_controller.h:145
corbo::SignalTargetInterface
Interface class for signal targets.
Definition: signal_target_interface.h:84
corbo::PredictiveController::_statistics
ControllerStatistics _statistics
Definition: predictive_controller.h:178
corbo::PredictiveController::getAvailableSignals
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Definition: predictive_controller.cpp:103
corbo::PredictiveController::PredictiveController
PredictiveController()
Definition: predictive_controller.cpp:54
corbo::PredictiveController::supportsAsynchronousControl
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
Definition: predictive_controller.h:133
corbo::PredictiveController::isPublishPrediction
const bool & isPublishPrediction() const
Definition: predictive_controller.h:144
corbo::PredictiveController::setNumOcpIterations
void setNumOcpIterations(int ocp_iter)
Definition: predictive_controller.h:142
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::PredictiveController::_output_control_sequence
bool _output_control_sequence
Definition: predictive_controller.h:185
corbo::PredictiveController::_initialized
bool _initialized
Definition: predictive_controller.h:188
corbo::PredictiveController::_x_ts
TimeSeries::Ptr _x_ts
Definition: predictive_controller.h:175
corbo::PredictiveController::providesFutureStates
bool providesFutureStates() const override
Definition: predictive_controller.h:110
corbo::PredictiveController::getControlInputDimension
int getControlInputDimension() const override
Return the control input dimension.
Definition: predictive_controller.h:102
corbo::PredictiveController::initialize
bool initialize(const StateVector &x, ReferenceTrajectoryInterface &expected_xref, ReferenceTrajectoryInterface &expected_uref, const Duration &expected_dt, const Time &t, ReferenceTrajectoryInterface *sref=nullptr) override
Initialize the controller.
Definition: predictive_controller.cpp:56
corbo::PredictiveController::getNumOcpIterations
const int & getNumOcpIterations() const
Definition: predictive_controller.h:141
corbo::PredictiveController::getControlDuration
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
Definition: predictive_controller.h:130
corbo::PredictiveController::getStatistics
ControllerStatistics::Ptr getStatistics() const override
Definition: predictive_controller.h:155
controller_interface.h
corbo::OptimalControlProblemInterface::Ptr
std::shared_ptr< OptimalControlProblemInterface > Ptr
Definition: optimal_control_problem_interface.h:91
corbo::PredictiveController::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: predictive_controller.cpp:68
corbo::PredictiveController::getOptimalControlProblem
OptimalControlProblemInterface::Ptr getOptimalControlProblem()
Definition: predictive_controller.h:117
corbo::PredictiveController::getAutoUpdatePreviousControl
bool getAutoUpdatePreviousControl() const
Definition: predictive_controller.h:151
corbo::PredictiveController::_ocp
OptimalControlProblemInterface::Ptr _ocp
Definition: predictive_controller.h:174
corbo::PredictiveController::getInstanceStatic
static Ptr getInstanceStatic()
Definition: predictive_controller.h:114
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::PredictiveController::setOptimalControlProblem
void setOptimalControlProblem(OptimalControlProblemInterface::Ptr ocp)
Definition: predictive_controller.h:116
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
Definition: controller_interface.h:105
corbo::PredictiveController::getStateDimension
int getStateDimension() const override
Return the dimension of the required plant state/output.
Definition: predictive_controller.h:104
corbo::PredictiveController::_output_state_sequence
bool _output_state_sequence
Definition: predictive_controller.h:186
optimal_control_problem_interface.h
corbo::PredictiveController::reset
void reset() override
Reset internal controller state and caches.
Definition: predictive_controller.cpp:116
corbo::PredictiveController::_auto_update_prev_control
bool _auto_update_prev_control
Definition: predictive_controller.h:180
corbo::ControllerStatistics
Definition: controllers/include/corbo-controllers/statistics.h:57
corbo::ControllerStatistics::Ptr
std::shared_ptr< ControllerStatistics > Ptr
Definition: controllers/include/corbo-controllers/statistics.h:81
corbo::PredictiveController::sendSignals
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
Definition: predictive_controller.cpp:121
corbo::PredictiveController::hasPiecewiseConstantControls
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
Definition: predictive_controller.h:106
corbo::PredictiveController::Ptr
std::shared_ptr< PredictiveController > Ptr
Definition: predictive_controller.h:97
corbo::ControllerInterface::StateVector
Eigen::VectorXd StateVector
Definition: controller_interface.h:107
corbo::PredictiveController::getInstance
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: predictive_controller.h:113
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::PredictiveController
Predictive controller.
Definition: predictive_controller.h:72
corbo::PredictiveController::_u_ts
TimeSeries::Ptr _u_ts
Definition: predictive_controller.h:176
corbo::PredictiveController::setAutoUpdatePreviousControl
void setAutoUpdatePreviousControl(bool enable)
Definition: predictive_controller.h:150
corbo::PredictiveController::setOutputControlSequenceLenght
void setOutputControlSequenceLenght(bool activate)
Definition: predictive_controller.h:147
corbo::PredictiveController::setOutputStateSequenceLenght
void setOutputStateSequenceLenght(bool activate)
Definition: predictive_controller.h:148
corbo::PredictiveController::providesFutureControls
bool providesFutureControls() const override
Definition: predictive_controller.h:108
corbo::PredictiveController::_publish_prediction
bool _publish_prediction
Definition: predictive_controller.h:183
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:03