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 
47 class DualModeController : public ControllerInterface
48 {
49  public:
50  using Ptr = std::shared_ptr<DualModeController>;
51 
52  DualModeController() = default;
53 
54  // implements interface method
55  int getControlInputDimension() const override { return _pred_controller.getControlInputDimension(); }
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_
corbo::DualModeController::_local_ctrl_active
bool _local_ctrl_active
Definition: dual_mode_controller.h:183
corbo::DualModeController::getInstance
ControllerInterface::Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
Definition: dual_mode_controller.h:119
corbo::SignalTargetInterface
Interface class for signal targets.
Definition: signal_target_interface.h:84
corbo::DualModeController::getControlInputDimension
int getControlInputDimension() const override
Return the control input dimension.
Definition: dual_mode_controller.h:99
corbo::DualModeController::_local_controller
ControllerInterface::Ptr _local_controller
Definition: dual_mode_controller.h:178
predictive_controller.h
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::DualModeController::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: dual_mode_controller.cpp:78
corbo::DualModeController::DualModeController
DualModeController()=default
corbo::DualModeController::_pred_controller
PredictiveController _pred_controller
Definition: dual_mode_controller.h:177
corbo::DualModeController::_switch_terminal_ball
bool _switch_terminal_ball
Definition: dual_mode_controller.h:181
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::DualModeController::getStateDimension
int getStateDimension() const override
Return the dimension of the required plant state/output.
Definition: dual_mode_controller.h:101
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::DualModeController::_gamma
double _gamma
Definition: dual_mode_controller.h:186
corbo::DualModeController::_initialized
bool _initialized
Definition: dual_mode_controller.h:192
corbo::DualModeController::supportsAsynchronousControl
bool supportsAsynchronousControl() const override
Specify whether the controllers step function is independent of dt and getControlDuration() returns a...
Definition: dual_mode_controller.h:143
corbo::DualModeController::_S
Eigen::MatrixXd _S
Definition: dual_mode_controller.h:185
corbo::DualModeController::_min_dt
double _min_dt
Definition: dual_mode_controller.h:188
controller_interface.h
corbo::DualModeController::providesFutureControls
bool providesFutureControls() const override
Definition: dual_mode_controller.h:108
corbo::DualModeController::getInstanceStatic
static Ptr getInstanceStatic()
Definition: dual_mode_controller.h:120
corbo::DualModeController::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: dual_mode_controller.cpp:55
corbo::DualModeController::getAvailableSignals
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Definition: dual_mode_controller.cpp:129
corbo::DualModeController::getStatistics
ControllerStatistics::Ptr getStatistics() const override
Definition: dual_mode_controller.h:153
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::ControllerInterface::Ptr
std::shared_ptr< ControllerInterface > Ptr
Definition: controller_interface.h:105
corbo::DualModeController::Ptr
std::shared_ptr< DualModeController > Ptr
Definition: dual_mode_controller.h:94
corbo::DualModeController::reset
void reset() override
Reset internal controller state and caches.
Definition: dual_mode_controller.cpp:137
corbo::DualModeController
Dual mode controller.
Definition: dual_mode_controller.h:69
corbo::DualModeController::_first_run
bool _first_run
Definition: dual_mode_controller.h:190
corbo::DualModeController::setWeightS
bool setWeightS(const Eigen::Ref< const Eigen::MatrixXd > &S)
Definition: dual_mode_controller.cpp:156
corbo::DualModeController::_switch_dt
bool _switch_dt
Definition: dual_mode_controller.h:180
corbo::PredictiveController::getStateDimension
int getStateDimension() const override
Return the dimension of the required plant state/output.
Definition: predictive_controller.h:104
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::DualModeController::hasPiecewiseConstantControls
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
Definition: dual_mode_controller.h:103
corbo::ControllerStatistics
Definition: controllers/include/corbo-controllers/statistics.h:57
corbo::DualModeController::sendSignals
void sendSignals(double t, SignalTargetInterface &signal_target, const std::string &ns="") const override
Definition: dual_mode_controller.cpp:145
corbo::ControllerStatistics::Ptr
std::shared_ptr< ControllerStatistics > Ptr
Definition: controllers/include/corbo-controllers/statistics.h:81
corbo::DualModeController::getControlDuration
double getControlDuration() const override
Return the duration for which the control u obtained from step() is valid (useful for asynchronous co...
Definition: dual_mode_controller.h:133
corbo::PredictiveController::hasPiecewiseConstantControls
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
Definition: predictive_controller.h:106
corbo::DualModeController::providesFutureStates
bool providesFutureStates() const override
Definition: dual_mode_controller.h:113
corbo::DualModeController::isInsideInTerminalBall
bool isInsideInTerminalBall(const Eigen::Ref< const Eigen::VectorXd > &x0, const Eigen::Ref< const Eigen::VectorXd > &xf) const
Definition: dual_mode_controller.cpp:123
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::DualModeController::setLocalController
void setLocalController(ControllerInterface::Ptr local_controller)
Definition: dual_mode_controller.h:140
corbo::PredictiveController
Predictive controller.
Definition: predictive_controller.h:72
corbo::DualModeController::_statistics
ControllerStatistics _statistics
Definition: dual_mode_controller.h:175
corbo::PredictiveController::providesFutureControls
bool providesFutureControls() const override
Definition: predictive_controller.h:108
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:05:45