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 
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 
137 
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_
const int & getNumOcpIterations() const
int getControlInputDimension() const override
Return the control input dimension.
ControllerStatistics::Ptr getStatistics() const override
Scalar * x
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
void setOutputStateSequenceLenght(bool activate)
void setPublishPrediction(bool publish)
const bool & isPublishPrediction() const
std::shared_ptr< OptimalControlProblemInterface > Ptr
Interface class for signal targets.
Representation of time stamps.
Definition: time.h:251
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
OptimalControlProblemInterface::Ptr _ocp
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
bool providesFutureStates() const override
int getStateDimension() const override
Return the dimension of the required plant state/output.
void reset() override
Reset internal controller state and caches.
OptimalControlProblemInterface::Ptr getOptimalControlProblem()
#define FACTORY_REGISTER_CONTROLLER(type)
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
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
void setAutoUpdatePreviousControl(bool enable)
void setOptimalControlProblem(OptimalControlProblemInterface::Ptr ocp)
void setOutputControlSequenceLenght(bool activate)
Interface class for reference trajectories.
bool providesFutureControls() const override
Interface class for controllers.
void setNumOcpIterations(int ocp_iter)
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
Representation of time durations.
Definition: time.h:106
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
std::shared_ptr< ControllerInterface > Ptr
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.


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:07:10