predictive_controller.cpp
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 
26 
28 #include <corbo-core/console.h>
29 
30 namespace corbo {
31 
33 
34 bool PredictiveController::initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
35  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref)
36 {
37  if (!_ocp || !_ocp->initialize())
38  {
39  PRINT_ERROR("PredictiveController::initialize(): no ocp specified or ocp initialization failed.");
40  return false;
41  }
42  _initialized = true;
43  return true;
44 }
45 
46 bool PredictiveController::step(const ControllerInterface::StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref,
47  const Duration& dt, const Time& t, TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence,
48  SignalTargetInterface* signal_target, ReferenceTrajectoryInterface* sref, ReferenceTrajectoryInterface* xinit,
49  ReferenceTrajectoryInterface* uinit, const std::string& ns)
50 {
51  if (!_initialized)
52  {
53  if (!initialize(x, xref, uref, dt, t, sref)) return false;
54  }
55 
57 
58  if (!_ocp) return false;
59 
60  if (_auto_update_prev_control) _ocp->setPreviousControlInputDt(dt.toSec());
61 
62  bool success = false;
63 
64  Time t_pre = Time::now();
65 
66  for (int i = 0; i < _num_ocp_iterations; ++i) success = _ocp->compute(x, xref, uref, sref, t, i == 0, signal_target, xinit, uinit, ns);
67 
69 
70  success = success && _ocp->getFirstControlInput(u);
71 
72  if (_auto_update_prev_control) _ocp->setPreviousControlInput(u, dt.toSec()); // cache control input for next step call
73 
74  _ocp->getTimeSeries(x_sequence, u_sequence);
75  _x_ts = x_sequence;
76  _u_ts = u_sequence;
77 
78  return success;
79 }
80 
81 void PredictiveController::getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns) const
82 {
84  {
85  signal_target.registerTimeSeries(ns + "prediction/x", _ocp->getStateDimension(), false);
86  signal_target.registerTimeSeries(ns + "prediction/u", _ocp->getControlInputDimension(), _ocp->isConstantControlAction());
87  signal_target.registerMeasurement(ns + "prediction/n", 1, {}, false);
88  signal_target.registerMeasurement(ns + "prediction/first_dt", 1, {}, false);
89  signal_target.registerMeasurement(ns + "prediction/objective", 1, {}, false);
90  signal_target.registerMeasurement(ns + "prediction/cpu_time", 1, {}, true);
91  }
92 }
93 
95 {
96  if (_ocp) _ocp->reset();
97 }
98 
99 void PredictiveController::sendSignals(double t, SignalTargetInterface& signal_target, const std::string& ns) const
100 {
102  {
103  if (_x_ts && _x_ts->getTimeDimension() > 0)
104  {
105  _x_ts->setTimeFromStart(t);
106  signal_target.sendTimeSeries(ns + "prediction/x", _x_ts);
107  }
108 
109  if (_u_ts && _u_ts->getTimeDimension() > 0)
110  {
111  _u_ts->setTimeFromStart(t);
112  signal_target.sendTimeSeries(ns + "prediction/u", _u_ts);
113  }
114 
115  signal_target.sendMeasurement(ns + "prediction/n", t, {(double)_ocp->getN()});
116  signal_target.sendMeasurement(ns + "prediction/first_dt", t, {_ocp->getFirstDt()});
117  signal_target.sendMeasurement(ns + "prediction/objective", t, {_ocp->getCurrentObjectiveValue()});
118  signal_target.sendMeasurement(ns + "prediction/cpu_time", t, {_statistics.step_time.toSec()});
119  }
120 }
121 
122 #ifdef MESSAGE_SUPPORT
123 void PredictiveController::toMessage(corbo::messages::PredictiveController& message) const
124 {
125  if (_ocp) _ocp->toMessage(*message.mutable_optimal_control_problem());
126  message.set_num_ocp_iterations(_num_ocp_iterations);
127  message.set_auto_update_prev_control(_auto_update_prev_control);
128  message.set_publish_prediction(_publish_prediction);
129 }
130 void PredictiveController::fromMessage(const corbo::messages::PredictiveController& message, std::stringstream* issues)
131 {
132  // ocp
133  if (!message.has_optimal_control_problem())
134  {
135  if (issues) *issues << "PredictiveController: no optimal control problem specified.\n";
136  return;
137  }
138 
139  _num_ocp_iterations = message.num_ocp_iterations();
140  _auto_update_prev_control = message.auto_update_prev_control();
141  _publish_prediction = message.publish_prediction();
142 
143  // construct object
144  std::string type;
145  util::get_oneof_field_type(message.optimal_control_problem(), "optimal_control_problem", type, false);
147  // import parameters
148  if (ocp)
149  {
150  ocp->fromMessage(message.optimal_control_problem(), issues);
152  }
153  else
154  {
155  if (issues) *issues << "PredictiveController: unknown optimal control problem specified.\n";
156  return;
157  }
158 }
159 #endif
160 
161 } // namespace corbo
corbo::Time::now
static Time now()
Retrieve current system time.
Definition: time.h:297
corbo::PredictiveController::_num_ocp_iterations
int _num_ocp_iterations
Definition: predictive_controller.h:182
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
predictive_controller.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::SignalTargetInterface::registerTimeSeries
virtual void registerTimeSeries(const std::string &unique_name, int value_dimension, bool zero_order_hold=false)=0
Register a time series type at current target.
corbo::ControllerStatistics::step_time
Duration step_time
Definition: controllers/include/corbo-controllers/statistics.h:83
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::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
console.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::Factory::instance
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:116
corbo::PredictiveController::_ocp
OptimalControlProblemInterface::Ptr _ocp
Definition: predictive_controller.h:174
corbo::ControllerInterface::ControlVector
Eigen::VectorXd ControlVector
Definition: controller_interface.h:108
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::SignalTargetInterface::registerMeasurement
virtual void registerMeasurement(const std::string &unique_name, int value_dimension, const std::vector< std::string > &value_labels={}, bool zero_order_hold=false)=0
Register a measurement type at current target.
corbo::PredictiveController::setOptimalControlProblem
void setOptimalControlProblem(OptimalControlProblemInterface::Ptr ocp)
Definition: predictive_controller.h:116
utilities.h
corbo::Factory::create
std::shared_ptr< Derived > create(const std::string &name, bool print_error=true) const
Create a shared instance of the desired object.
Definition: factory.h:137
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::Duration::toSec
double toSec() const
Return duration in seconds.
Definition: time.h:160
corbo::Time
Representation of time stamps.
Definition: time.h:273
corbo::PredictiveController::sendSignals
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
Definition: predictive_controller.cpp:121
corbo::ControllerInterface::StateVector
Eigen::VectorXd StateVector
Definition: controller_interface.h:107
corbo::TimeSeries::Ptr
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:108
corbo::PredictiveController::_u_ts
TimeSeries::Ptr _u_ts
Definition: predictive_controller.h:176
PRINT_ERROR
#define PRINT_ERROR(msg)
Print msg-stream as error msg.
Definition: console.h:173
corbo::PredictiveController::_publish_prediction
bool _publish_prediction
Definition: predictive_controller.h:183


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