dual_mode_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_DUAL_MODE_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_DUAL_MODE_CONTROLLER_H_
27 
30 
31 #include <memory>
32 
33 namespace corbo {
34 
48 {
49  public:
50  using Ptr = std::shared_ptr<DualModeController>;
51 
52  DualModeController() = default;
53 
54  // implements interface method
56  // implements interface method
57  int getStateDimension() const override { return _pred_controller.getStateDimension(); }
58  // implements interface method
59  bool hasPiecewiseConstantControls() const override
60  {
61  return _local_ctrl_active ? _local_controller->hasPiecewiseConstantControls() : _pred_controller.hasPiecewiseConstantControls();
62  }
63  // implements interface method
64  bool providesFutureControls() const override
65  {
66  return _local_ctrl_active ? _local_controller->providesFutureControls() : _pred_controller.providesFutureControls();
67  } // TODO(roesmann): how should we handle this with the LQR?
68  // implements interface method
69  bool providesFutureStates() const override
70  {
72  } // TODO(roesmann): how should we handle this with the LQR?
73 
74  // implements interface method
75  ControllerInterface::Ptr getInstance() const override { return std::make_shared<DualModeController>(); }
76  static Ptr getInstanceStatic() { return std::make_shared<DualModeController>(); }
77 
78  // implements interface method
79  bool initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
80  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref = nullptr) override;
81 
82  // implements interface method
83  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
84  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
85  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
86  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override;
87 
88  // implements interface method
89  double getControlDuration() const override
90  {
92  }
93 
95 
96  void setLocalController(ControllerInterface::Ptr local_controller) { _local_controller = local_controller; }
97 
98  // implements interface method
99  bool supportsAsynchronousControl() const override { return true; }
100 
101  // implements interface method
102  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override;
103 
104  // implements interface method
105  void reset() override;
106 
107  void sendSignals(double t, SignalTargetInterface& signal_target, const std::string& ns = "") const override;
108 
110  {
111  return std::make_shared<ControllerStatistics>(_statistics);
112  } // TODO(roesmann): make_shared?
113 
114 #ifdef MESSAGE_SUPPORT
115  void toMessage(corbo::messages::DualModeController& message) const;
116  void fromMessage(const corbo::messages::DualModeController& message, std::stringstream* issues = nullptr);
117 
118  // implements interface method
119  void toMessage(corbo::messages::Controller& message) const override { toMessage(*message.mutable_dual_mode_controller()); }
120  // implements interface method
121  void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) override
122  {
123  fromMessage(message.dual_mode_controller(), issues);
124  }
125 #endif
126 
127  protected:
129 
130  private:
132 
135 
136  bool _switch_dt = false;
137  bool _switch_terminal_ball = false;
138 
139  bool _local_ctrl_active = false;
140 
141  Eigen::MatrixXd _S;
142  double _gamma = 0.0;
143 
144  double _min_dt = 0;
145 
146  bool _first_run = true;
147 
148  bool _initialized = false;
149 };
150 
152 
153 } // namespace corbo
154 
155 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_DUAL_MODE_CONTROLLER_H_
int getControlInputDimension() const override
Return the control input dimension.
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Scalar * x
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.
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
Dual mode controller.
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
int getStateDimension() const override
Return the dimension of the required plant state/output.
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
Interface class for signal targets.
Representation of time stamps.
Definition: time.h:251
bool providesFutureStates() const override
int getControlInputDimension() const override
Return the control input dimension.
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
bool providesFutureStates() const override
bool setWeightS(const Eigen::Ref< const Eigen::MatrixXd > &S)
void reset() override
Reset internal controller state and caches.
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
int getStateDimension() const override
Return the dimension of the required plant state/output.
bool providesFutureControls() const override
ControllerStatistics::Ptr getStatistics() const override
#define FACTORY_REGISTER_CONTROLLER(type)
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
bool isInsideInTerminalBall(const Eigen::Ref< const Eigen::VectorXd > &x0, const Eigen::Ref< const Eigen::VectorXd > &xf) const
ControllerInterface::Ptr _local_controller
Interface class for reference trajectories.
PredictiveController _pred_controller
bool providesFutureControls() const override
void setLocalController(ControllerInterface::Ptr local_controller)
ControllerStatistics _statistics
Interface class for controllers.
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
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
Representation of time durations.
Definition: time.h:106
std::shared_ptr< ControllerInterface > Ptr


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