UdonLibrary 1.0.0
機械システム研究部 C++ ライブラリ
読み取り中…
検索中…
一致する文字列を見つけられません
SpeedPid.hpp
[詳解]
1//
2// 速度型PIDコントローラクラス
3//
4
5#ifndef DEF_SpeedPidController_H
6#define DEF_SpeedPidController_H
7
8#include "Math.hpp"
10
11namespace Udon
12{
15 {
16 public:
17 struct Parameter
18 {
19 double p;
20 double i;
21 double d;
22 };
23
24 private:
25 Parameter constant;
26
27 Udon::Optional<Parameter> requestConstant;
28
29 Parameter power;
30
31 double lastPowerPro;
32 double lastError;
33 double rowPassDif;
34 double output;
35 const double MAX_POWER;
36 const double INTERVAL_S;
37
38 public:
44 SpeedPidController(double kPro, double kInt, double kDif,
45 unsigned long callInterval_us,
46 double maxPower = 10000) noexcept
47 : constant{ kPro, kInt, kDif }
48 , requestConstant{}
49 , power{}
50 , lastPowerPro(0.0)
51 , lastError()
52 , rowPassDif()
53 , output()
54 , MAX_POWER(maxPower)
55 , INTERVAL_S(callInterval_us / 1000000.0)
56 {
57 }
58
63 void update(double controlValue, double targetValue) noexcept
64 {
65 // 係数の適用
66 const auto coefficient = requestConstant ? *requestConstant : constant;
67 requestConstant.reset();
68
69 // 偏差の計算
70 const double error = targetValue - controlValue;
71
72 // 比例量の計算
73 power.p = (error - lastError) / INTERVAL_S * coefficient.p;
74
75 // 積分量の計算
76 power.i = error * coefficient.i;
77
78 // 微分量の計算
79 power.d = (power.p - lastPowerPro) / INTERVAL_S;
80
81 //ローパスフィルタの計算
82 rowPassDif += (power.d - rowPassDif) / 8 * coefficient.d;
83
84 const double deltaPower = power.p + power.i + rowPassDif;
85
86 output = Udon::Constrain(output + deltaPower, -MAX_POWER, MAX_POWER);
87
88 // 偏差の保存
89 lastPowerPro = power.p;
90 lastError = error;
91 }
92
95 double getPower() const noexcept
96 {
97 return output;
98 }
99
104 double getPower(double min, double max) const noexcept
105 {
106 return Udon::Constrain(getPower(), min, max);
107 }
108
113 double operator()(double controlValue, double targetValue) noexcept
114 {
115 update(controlValue, targetValue);
116 return getPower();
117 }
118
125 double operator()(double controlValue, double targetValue, double min,
126 double max) noexcept
127 {
128 update(controlValue, targetValue);
129 return getPower(min, max);
130 }
131
134 void clearPower() noexcept
135 {
136 power = {};
137 output = 0.0;
138 lastPowerPro = 0.0;
139 rowPassDif = 0.0;
140 lastError = 0.0;
141 }
144 void requestParamPro(double value) noexcept
145 {
146 if (requestConstant)
147 {
148 requestConstant->p = value;
149 }
150 else
151 {
152 requestConstant = Parameter{ value, constant.i, constant.d };
153 }
154 }
155
158 void requestParamInt(double value) noexcept
159 {
160 if (requestConstant)
161 {
162 requestConstant->i = value;
163 }
164 else
165 {
166 requestConstant = Parameter{ constant.p, value, constant.d };
167 }
168 }
169
172 void requestParamDif(double value) noexcept
173 {
174 if (requestConstant)
175 {
176 requestConstant->d = value;
177 }
178 else
179 {
180 requestConstant = Parameter{ constant.p, constant.i, value };
181 }
182 }
183
186 void requestParam(const Parameter& value) noexcept
187 {
188 requestConstant = value;
189 }
190
193 void setParamPro(double value) noexcept { constant.p = value; }
194
197 void setParamInt(double value) noexcept { constant.i = value; }
198
201 void setParamDif(double value) noexcept { constant.d = value; }
202
205 void setParam(const Parameter& value) noexcept { constant = value; }
206
209 double getParamPro() const noexcept { return constant.p; }
210
213 double getParamInt() const noexcept { return constant.i; }
214
217 double getParamDif() const noexcept { return constant.d; }
218
221 const Parameter& getParam() const noexcept { return constant; }
222
225 double getPowerPro() const noexcept { return power.p; }
226
229 double getPowerInt() const noexcept { return power.i; }
230
233 double getPowerDif() const noexcept { return power.d; }
234 };
235} // namespace Udon
236
237#endif
オプショナル型
Definition Optional.hpp:62
void reset() noexcept(std::is_nothrow_destructible< ValueType >::value)
無効状態にする (トリビアルな型)
Definition Optional.hpp:491
速度型PID制御器
Definition SpeedPid.hpp:15
double getPowerInt() const noexcept
積分量の取得
Definition SpeedPid.hpp:229
void requestParamDif(double value) noexcept
一周期のみ適用する微分係数の設定
Definition SpeedPid.hpp:172
double getPowerDif() const noexcept
微分量の取得
Definition SpeedPid.hpp:233
void requestParam(const Parameter &value) noexcept
一周期のみ適用する係数の設定
Definition SpeedPid.hpp:186
void clearPower() noexcept
操作量のクリア
Definition SpeedPid.hpp:134
SpeedPidController(double kPro, double kInt, double kDif, unsigned long callInterval_us, double maxPower=10000) noexcept
コンストラクタ
Definition SpeedPid.hpp:44
const Parameter & getParam() const noexcept
係数の取得
Definition SpeedPid.hpp:221
double getParamPro() const noexcept
比例係数の取得
Definition SpeedPid.hpp:209
double operator()(double controlValue, double targetValue) noexcept
更新、操作量の取得
Definition SpeedPid.hpp:113
void setParamPro(double value) noexcept
比例係数の設定
Definition SpeedPid.hpp:193
void requestParamInt(double value) noexcept
一周期のみ適用する積分係数の設定
Definition SpeedPid.hpp:158
double getPowerPro() const noexcept
比例量の取得
Definition SpeedPid.hpp:225
double getParamInt() const noexcept
積分係数の取得
Definition SpeedPid.hpp:213
double operator()(double controlValue, double targetValue, double min, double max) noexcept
更新、操作量の取得
Definition SpeedPid.hpp:125
double getPower() const noexcept
操作量の取得
Definition SpeedPid.hpp:95
void update(double controlValue, double targetValue) noexcept
データ更新
Definition SpeedPid.hpp:63
void setParam(const Parameter &value) noexcept
係数の設定
Definition SpeedPid.hpp:205
void requestParamPro(double value) noexcept
一周期のみ適用する比例係数の設定
Definition SpeedPid.hpp:144
double getPower(double min, double max) const noexcept
操作量の取得
Definition SpeedPid.hpp:104
void setParamInt(double value) noexcept
積分係数の設定
Definition SpeedPid.hpp:197
void setParamDif(double value) noexcept
微分係数の設定
Definition SpeedPid.hpp:201
double getParamDif() const noexcept
微分係数の取得
Definition SpeedPid.hpp:217
Definition Bit.hpp:12
constexpr A Constrain(const A &amt, const B &low, const C &high)
値を指定された範囲内に収める (std::clamp)
Definition Math.hpp:68
Definition SpeedPid.hpp:18
double d
Definition SpeedPid.hpp:21
double p
Definition SpeedPid.hpp:19
double i
Definition SpeedPid.hpp:20