optimal_control_problem_interface.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_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_OPTIMAL_CONTROL_PROBLEM_INTERFACE_H_
26 #define SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_OPTIMAL_CONTROL_PROBLEM_INTERFACE_H_
27 
28 #include <corbo-core/factory.h>
31 #include <corbo-core/time.h>
32 #include <corbo-core/types.h>
33 
35 
36 #ifdef MESSAGE_SUPPORT
37 #include <corbo-communication/messages/optimal_control/optimal_control_problem.pb.h>
38 #endif
39 
40 #include <memory>
41 
42 namespace corbo {
43 
45 {
46  public:
47  using Ptr = std::shared_ptr<OptimalControlProblemInterface>;
48  using UPtr = std::unique_ptr<OptimalControlProblemInterface>;
49  using StateVector = Eigen::VectorXd;
50  using ControlVector = Eigen::VectorXd;
51 
53 
54  virtual Ptr getInstance() const = 0;
55 
56  virtual void reset() = 0;
57 
58  virtual int getControlInputDimension() const = 0;
59  virtual int getStateDimension() const = 0;
60  virtual int getN() const = 0;
61 
62  virtual bool initialize() { return true; }
63 
65  ReferenceTrajectoryInterface* sref, const Time& t, bool new_run = true, SignalTargetInterface* signal_target = nullptr,
66  ReferenceTrajectoryInterface* xinit = nullptr, ReferenceTrajectoryInterface* uinit = nullptr,
67  const std::string& ns = "") = 0;
68 
69  virtual bool getFirstControlInput(ControlVector& u0) const = 0;
70  virtual double getFirstDt() const = 0;
71 
72  virtual bool isConstantControlAction() const = 0;
73 
74  virtual double getCurrentObjectiveValue() { return -1; }
75 
76  // TODO(roesmann): someday we should change this to return a time-series, e.g. a std::pair<TS,TS>, because pre-allocating a shared pointer is ugly
77  virtual void getTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max = CORBO_INF_DBL) = 0;
78  // virtual std::pair<TimeSeries::Ptr, TimeSeries::Ptr> getTimeSeries(bool states = true, bool controls = true, double t_max = CORBO_INF_DBL) = 0;
79 
80  virtual bool providesFutureControls() const = 0;
81  virtual bool providesFutureStates() const = 0;
82 
83  virtual void setPreviousControlInput(const Eigen::Ref<const ControlVector>& u_prev, double dt) {}
84  virtual void setPreviousControlInputDt(double dt) {}
85 
86  virtual OptimalControlProblemStatistics::Ptr getStatistics() const { return {}; }
87 
88 #ifdef MESSAGE_SUPPORT
89  virtual void toMessage(corbo::messages::OptimalControlProblem& message) const {}
90  virtual void fromMessage(const corbo::messages::OptimalControlProblem& message, std::stringstream* issues = nullptr) {}
91 #endif
92 };
93 
95 #define FACTORY_REGISTER_OCP(type) FACTORY_REGISTER_OBJECT(type, OptimalControlProblemInterface)
96 
97 } // namespace corbo
98 
99 #endif // SRC_OPTIMAL_CONTROL_INCLUDE_CORBO_OPTIMAL_CONTROL_OPTIMAL_CONTROL_PROBLEM_INTERFACE_H_
virtual bool providesFutureControls() const =0
virtual bool getFirstControlInput(ControlVector &u0) const =0
Generic factory object.
Definition: factory.h:68
virtual OptimalControlProblemStatistics::Ptr getStatistics() const
Scalar * x
virtual bool isConstantControlAction() const =0
virtual Ptr getInstance() const =0
virtual double getFirstDt() const =0
std::shared_ptr< OptimalControlProblemInterface > Ptr
virtual void getTimeSeries(TimeSeries::Ptr x_sequence, TimeSeries::Ptr u_sequence, double t_max=CORBO_INF_DBL)=0
Interface class for signal targets.
Representation of time stamps.
Definition: time.h:251
constexpr const double CORBO_INF_DBL
Representation for infinity (double version)
std::unique_ptr< OptimalControlProblemInterface > UPtr
virtual int getStateDimension() const =0
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
Interface class for reference trajectories.
virtual int getControlInputDimension() const =0
virtual bool compute(const StateVector &x, ReferenceTrajectoryInterface &xref, ReferenceTrajectoryInterface &uref, ReferenceTrajectoryInterface *sref, const Time &t, bool new_run=true, SignalTargetInterface *signal_target=nullptr, ReferenceTrajectoryInterface *xinit=nullptr, ReferenceTrajectoryInterface *uinit=nullptr, const std::string &ns="")=0
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
virtual void setPreviousControlInput(const Eigen::Ref< const ControlVector > &u_prev, double dt)
virtual bool providesFutureStates() const =0


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