simple_state_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 
27 #include <corbo-core/console.h>
28 
29 #include <algorithm>
30 
31 namespace corbo {
32 
34 
36 
37 bool SimpleStateController::initialize(const StateVector& x, ReferenceTrajectoryInterface& expected_xref, ReferenceTrajectoryInterface& expected_uref,
38  const Duration& expected_dt, const Time& t, ReferenceTrajectoryInterface* sref)
39 {
40  assert(x.rows() == expected_xref.getDimension() && "Dimension mismatch in controller: current state x and reference");
41  assert(getStateDimension() == property::INHERITED || x.rows() == getStateDimension());
42 
43  return true;
44 }
45 
46 bool SimpleStateController::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  // const int q = uref.getDimension();
52  ControlVector u;
53 
55  xref.getReference(t, xref_vec);
57  uref.getReference(t, uref_vec);
58 
59  if (_V.rows() > 0 && _V.cols() > 0)
60  {
61  u = -_K * x + _V * xref_vec;
62 
63  if (signal_target && _publish_error)
64  {
65  signal_target->sendMeasurement(ns + "controller/error_norml2", t.toSec(), {x.norm()});
66  }
67  }
68  else
69  {
70  StateVector state_error = xref_vec - x;
71 
72  u = _K * state_error + uref_vec;
73 
74  if (signal_target && _publish_error)
75  {
76  signal_target->sendMeasurement(ns + "controller/error_norml2", t.toSec(), {state_error.norm()});
77  }
78  }
79 
80  u_sequence->clear();
81  x_sequence->clear();
82  u_sequence->add(0.0, u);
83  x_sequence->add(0.0, x);
84 
85  return true;
86 }
87 
88 void SimpleStateController::getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns) const
89 {
90  if (_publish_error)
91  {
92  signal_target.registerMeasurement(ns + "controller/error_norml2", 1);
93  }
94 }
95 
97 
98 #ifdef MESSAGE_SUPPORT
99 void SimpleStateController::toMessage(corbo::messages::Controller& message) const
100 {
101  // feedback gain matrix K
102  message.mutable_simple_state_controller()->mutable_k()->Resize(_K.rows() * _K.cols(), 0);
103  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.mutable_simple_state_controller()->mutable_k()->mutable_data(), _K.rows(),
104  _K.cols()) = _K;
105 
106  // filter matrix V
107  message.mutable_simple_state_controller()->mutable_v()->Resize(_V.rows() * _V.cols(), 0);
108  Eigen::Map<Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.mutable_simple_state_controller()->mutable_v()->mutable_data(), _V.rows(),
109  _V.cols()) = _V;
110 
111  message.mutable_simple_state_controller()->set_state_dim(getStateDimension());
112 
113  // publish error
114  message.mutable_simple_state_controller()->set_publish_error(_publish_error);
115 }
116 
117 void SimpleStateController::fromMessage(const corbo::messages::Controller& message, std::stringstream* issues)
118 {
119  int state_dim = 0;
120  int control_dim = 0;
121  int output_dim = 0;
122 
123  if (message.simple_state_controller().v_size() == 0)
124  {
125  // no prefilter specified
126  state_dim = message.simple_state_controller().state_dim();
127  output_dim = state_dim;
128  control_dim = message.simple_state_controller().k_size() / state_dim;
129  if (message.simple_state_controller().output_dim() != output_dim && issues)
130  {
131  *issues << "SimpleStateController: output_dim must match state_dim since no prefilter matrix V is specified.\n";
132  }
133  }
134  else
135  {
136  output_dim = message.simple_state_controller().output_dim();
137  control_dim = message.simple_state_controller().v_size() / output_dim;
138  state_dim = message.simple_state_controller().state_dim();
139  if (control_dim != message.simple_state_controller().k_size() / state_dim && issues)
140  {
141  *issues << "SimpleStateController: dimension mismatch. cols(K) must be equal to cols(V).\n";
142  }
143 
144  if (output_dim * control_dim == message.simple_state_controller().v_size())
145  {
146  setFilterMatrixV(Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.simple_state_controller().v().data(),
147  control_dim, output_dim));
148  }
149  else if (issues)
150  *issues << "SimpleStateController: invalid size of filter matrix V.\n";
151  }
152  if (state_dim * control_dim == message.simple_state_controller().k_size())
153  {
155  Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(message.simple_state_controller().k().data(), control_dim, state_dim));
156  }
157  else if (issues)
158  *issues << "SimpleStateController: invalid size of feedback gain matrix K.\n";
159 
160  // publish error
161  _publish_error = message.simple_state_controller().publish_error();
162 }
163 #endif
164 
165 } // namespace corbo
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::SimpleStateController::_publish_error
bool _publish_error
Definition: simple_state_controller.h:142
corbo::SimpleStateController::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: simple_state_controller.cpp:59
Eigen::RowMajor
@ RowMajor
Definition: Constants.h:322
console.h
corbo::SimpleStateController::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: simple_state_controller.cpp:68
corbo::SimpleStateController::reset
void reset() override
Reset internal controller state and caches.
Definition: simple_state_controller.cpp:118
corbo::ControllerInterface::ControlVector
Eigen::VectorXd ControlVector
Definition: controller_interface.h:108
x
Scalar * x
Definition: level1_cplx_impl.h:89
corbo::property::INHERITED
constexpr const int INHERITED
Inherit property.
Definition: core/include/corbo-core/types.h:84
corbo::SimpleStateController::_V
Eigen::MatrixXd _V
Definition: simple_state_controller.h:144
corbo::SimpleStateController::_K
Eigen::MatrixXd _K
Definition: simple_state_controller.h:143
corbo::SimpleStateController::getStateDimension
int getStateDimension() const override
Return the dimension of the required plant state/output.
Definition: simple_state_controller.h:98
simple_state_controller.h
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
utilities.h
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::SimpleStateController::getAvailableSignals
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Definition: simple_state_controller.cpp:110
corbo::SimpleStateController::setFilterMatrixV
void setFilterMatrixV(const Eigen::Ref< const Eigen::MatrixXd > &V)
Set reference filter matrix V [control input dimension x output dimension].
Definition: simple_state_controller.cpp:57
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:178
corbo::ReferenceTrajectoryInterface::OutputVector
Eigen::VectorXd OutputVector
Definition: reference_trajectory.h:108
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::SimpleStateController::setGainMatrixK
void setGainMatrixK(const Eigen::Ref< const Eigen::MatrixXd > &K)
Set feedback gain matrix K [control input dimension x state dimension].
Definition: simple_state_controller.cpp:55


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