pid_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_PID_CONTROLLER_H_
26 #define SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PID_CONTROLLER_H_
27 
29 #include <memory>
30 
31 namespace corbo {
32 
47 {
48  public:
49  PidController();
50 
51  // implements interface method
52  int getControlInputDimension() const override { return _num_parallel_pid; }
53  // implements interface method
54  int getStateDimension() const override { return _num_parallel_pid; }
55  // implements interface method
56  bool hasPiecewiseConstantControls() const override { return false; }
57  // implements interface method
58  bool providesFutureControls() const override { return false; }
59  // implements interface method
60  bool providesFutureStates() const override { return false; }
61 
62  // implements interface method
63  Ptr getInstance() const override { return std::make_shared<PidController>(); }
65  static Ptr getInstanceStatic() { return std::make_shared<PidController>(); }
66 
67  const double& getGainP() const { return _p_gain; }
69  void setGainP(double p_gain) { _p_gain = p_gain; }
71  const double& getGainI() const { return _i_gain; }
72  void setGainI(double i_gain) { _i_gain = i_gain; }
74  const double& getGainD() const { return _d_gain; }
75  void setGainD(double d_gain) { _d_gain = d_gain; }
76 
77  void setNumParallelPid(int num_parallel_pid)
78  {
79  _num_parallel_pid = num_parallel_pid;
80  _p_error.resize(_num_parallel_pid, 0.0);
81  _i_error.resize(_num_parallel_pid, 0.0);
82  _d_error.resize(_num_parallel_pid, 0.0);
83  }
84 
85  // implements interface method
86  bool step(const StateVector& x, ReferenceTrajectoryInterface& xref, ReferenceTrajectoryInterface& uref, const Duration& dt, const Time& t,
87  TimeSeries::Ptr u_sequence, TimeSeries::Ptr x_sequence, SignalTargetInterface* signal_target = nullptr,
88  ReferenceTrajectoryInterface* sref = nullptr, ReferenceTrajectoryInterface* xinit = nullptr,
89  ReferenceTrajectoryInterface* uinit = nullptr, const std::string& ns = "") override;
90 
91  // implements interface method
92  void getAvailableSignals(SignalTargetInterface& signal_target, const std::string& ns = "") const override;
93 
94  ControllerStatistics::Ptr getStatistics() const override { return {}; }
95 
96 #ifdef MESSAGE_SUPPORT
97  // implements interface method
98  void toMessage(corbo::messages::Controller& message) const override;
99  // implements interface method
100  void fromMessage(const corbo::messages::Controller& message, std::stringstream* issues = nullptr) override;
101 #endif
102 
103  // implements interface method
104  void reset() override;
105 
107  void publishError(bool active) { _publish_error = active; }
108 
109  private:
110  // parameters
111  double _p_gain = 0.2;
112  double _i_gain = 0.0;
113  double _d_gain = 0.0;
114 
115  // internal states
116  std::vector<double> _p_error;
117  std::vector<double> _i_error;
118  std::vector<double> _d_error;
119  // double _control_error_last = 0;
120 
122 
123  bool _publish_error = true;
124 };
125 
127 
128 } // namespace corbo
129 
130 #endif // SRC_CONTROLLERS_INCLUDE_CORBO_CONTROLLERS_PID_CONTROLLER_H_
std::vector< double > _i_error
void publishError(bool active)
Specify whether the control error should be published via signal.
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
void setGainP(double p_gain)
Set proportional gain.
Scalar * x
void setGainD(double d_gain)
void setGainI(double i_gain)
bool providesFutureStates() const override
std::vector< double > _d_error
void setNumParallelPid(int num_parallel_pid)
ControllerStatistics::Ptr getStatistics() const override
bool hasPiecewiseConstantControls() const override
Return true if the controller returns piecewise constant control pieces.
void getAvailableSignals(SignalTargetInterface &signal_target, const std::string &ns="") const override
Retrieve available signals from the controller.
Interface class for signal targets.
Representation of time stamps.
Definition: time.h:251
static Ptr getInstanceStatic()
Return a newly created shared instance of the implemented class (static method)
const double & getGainP() const
std::vector< double > _p_error
bool providesFutureControls() const override
PID controller.
int getControlInputDimension() const override
Return the control input dimension.
#define FACTORY_REGISTER_CONTROLLER(type)
Ptr getInstance() const override
Return a newly created shared instance of the implemented class.
void reset() override
Reset internal controller state and caches.
Interface class for reference trajectories.
int getStateDimension() const override
Return the dimension of the required plant state/output.
Interface class for controllers.
std::shared_ptr< TimeSeries > Ptr
Definition: time_series.h:64
Representation of time durations.
Definition: time.h:106
const double & getGainI() const
Set integral gain.
std::shared_ptr< ControllerInterface > Ptr
const double & getGainD() const
Set differential gain.


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