libxr 1.0
Want to be the best embedded framework
Loading...
Searching...
No Matches
LibXR::PID< Scalar > Class Template Reference

通用 PID 控制器类。 Generic PID controller. More...

#include <pid.hpp>

Collaboration diagram for LibXR::PID< Scalar >:

Data Structures

struct  Param
 PID 参数结构体。 Structure holding PID parameters. More...
 

Public Member Functions

 PID (const Param PARAM)
 构造 PID 控制器。 Construct a PID controller.
 
Scalar Calculate (Scalar sp, Scalar fb, Scalar dt)
 使用反馈值计算 PID 输出。 Compute output from feedback only. out = k(p*err + i*∫err*dt - d*(fb-last_fb)/dt)
 
Scalar Calculate (Scalar sp, Scalar fb, Scalar fb_dot, Scalar dt)
 使用外部导数计算 PID 输出。 Compute output using external feedback derivative. out = k(p*err + i*∫err*dt - d*fb_dot*dt)
 
void SetK (Scalar k)
 设置全局比例系数 Set global proportional gain
 
void SetP (Scalar p)
 设置 P 项系数 Set proportional gain
 
void SetI (Scalar i)
 设置 I 项系数 Set integral gain
 
void SetD (Scalar d)
 设置 D 项系数 Set derivative gain
 
void SetILimit (Scalar limit)
 设置积分限幅 Set integral limit
 
void SetOutLimit (Scalar limit)
 设置输出限幅 Set output limit
 
Scalar K () const
 获取全局比例系数 Get global proportional gain
 
Scalar P () const
 获取 P 项系数 Get proportional gain
 
Scalar I () const
 获取 I 项系数 Get integral gain
 
Scalar D () const
 获取 D 项系数 Get derivative gain
 
Scalar ILimit () const
 获取积分限幅 Get integral limit
 
Scalar OutLimit () const
 获取输出限幅 Get output limit
 
Scalar LastError () const
 获取上一次误差 Get last error
 
Scalar LastFeedback () const
 获取上一次反馈值 Get last feedback
 
Scalar LastOutput () const
 获取上一次输出 Get last output
 
Scalar LastDerivative () const
 获取上一次导数 Get last derivative
 
void Reset ()
 重置控制器状态。 Reset all internal states.
 
void SetIntegralError (Scalar err)
 设置累计误差 Set integral error
 
Scalar GetIntegralError () const
 获取累计误差 Get integral error
 
void SetFeedForward (Scalar feed_forward)
 设置前馈项 Set feedforward
 
Scalar GetFeedForward () const
 获取前馈项 Get feedforward
 

Private Attributes

Param param_
 PID 参数 PID parameter set.
 
Scalar i_ = 0
 积分状态 Integral state
 
Scalar last_err_ = 0
 上次误差 Last error
 
Scalar last_fb_ = 0
 上次反馈 Last feedback
 
Scalar last_der_ = 0
 上次导数 Last derivative
 
Scalar last_out_ = 0
 上次输出 Last output
 
Scalar feed_forward_ = 0
 前馈项 Feedforward term
 

Detailed Description

template<typename Scalar = DefaultScalar>
class LibXR::PID< Scalar >

通用 PID 控制器类。 Generic PID controller.

支持周期角度处理、积分限幅与输出限幅,适用于基础控制应用。 Supports cyclic inputs, integral/output saturation. No derivative filtering.

Template Parameters
Scalar控制器标量类型,默认为 DefaultScalar。 Scalar type for internal calculations.

Definition at line 26 of file pid.hpp.

Constructor & Destructor Documentation

◆ PID()

template<typename Scalar = DefaultScalar>
LibXR::PID< Scalar >::PID ( const Param  PARAM)
inline

构造 PID 控制器。 Construct a PID controller.

Parameters
paramPID 参数结构体。 PID parameter struct.

Definition at line 51 of file pid.hpp.

51: param_(std::move(PARAM)) { Reset(); }
void Reset()
重置控制器状态。 Reset all internal states.
Definition pid.hpp:214
Param param_
PID 参数 PID parameter set.
Definition pid.hpp:252
constexpr auto min(T1 a, T2 b) -> typename std::common_type< T1, T2 >::type
计算两个数的最小值

Member Function Documentation

◆ Calculate() [1/2]

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::Calculate ( Scalar  sp,
Scalar  fb,
Scalar  dt 
)
inline

使用反馈值计算 PID 输出。 Compute output from feedback only. out = k(p*err + i*∫err*dt - d*(fb-last_fb)/dt)

Parameters
sp期望值 Setpoint
fb反馈值 Feedback
dt控制周期(秒) Time step in seconds
Returns
控制器输出 Controller output

Definition at line 63 of file pid.hpp.

64 {
65 if (!std::isfinite(sp) || !std::isfinite(fb) || !std::isfinite(dt))
66 {
67 return last_out_;
68 }
69
70 // Compute error
73
74 // Derivative from feedback change
75 fb *= param_.k;
76 Scalar d = (fb - last_fb_) / dt;
77 if (!std::isfinite(d))
78 {
79 d = 0;
80 }
81
82 // Compute PD
83 Scalar output = (k_err * param_.p) - (d * param_.d);
84
85 // Integrate if within limits
86 Scalar i_term = i_ + k_err * dt;
88
89 if (param_.i > PID_SIGMA && std::isfinite(i_term))
90 {
91 if (std::abs(output + i_out) <= param_.out_limit &&
92 std::abs(i_term) <= param_.i_limit)
93 {
94 i_ = i_term;
95 }
96 }
97
98 // Apply output limits
99 output += i_out;
101 if (std::isfinite(output) && param_.out_limit > PID_SIGMA)
102 {
103 output = std::clamp(output, -param_.out_limit, param_.out_limit);
104 }
105
106 // Store states
107 last_err_ = err;
108 last_fb_ = fb;
110 last_der_ = d;
111 return output;
112 }
Scalar last_err_
上次误差 Last error
Definition pid.hpp:254
Scalar last_fb_
上次反馈 Last feedback
Definition pid.hpp:255
Scalar last_der_
上次导数 Last derivative
Definition pid.hpp:256
Scalar last_out_
上次输出 Last output
Definition pid.hpp:257
Scalar i_
积分状态 Integral state
Definition pid.hpp:253
Scalar feed_forward_
前馈项 Feedforward term
Definition pid.hpp:258
Scalar i_limit
积分限幅 Integral limit
Definition pid.hpp:39
Scalar out_limit
输出限幅 Output limit
Definition pid.hpp:40
Scalar p
比例项 Proportional gain
Definition pid.hpp:36
bool cycle
是否处理周期误差 Whether input is cyclic
Definition pid.hpp:41
Scalar k
全局比例因子 Global gain
Definition pid.hpp:35
Scalar i
积分项 Integral gain
Definition pid.hpp:37
Scalar d
微分项 Derivative gain
Definition pid.hpp:38

◆ Calculate() [2/2]

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::Calculate ( Scalar  sp,
Scalar  fb,
Scalar  fb_dot,
Scalar  dt 
)
inline

使用外部导数计算 PID 输出。 Compute output using external feedback derivative. out = k(p*err + i*∫err*dt - d*fb_dot*dt)

Parameters
sp期望值 Setpoint
fb反馈值 Feedback
fb_dot反馈导数 Feedback rate
dt控制周期 Delta time
Returns
控制器输出 Controller output

Definition at line 125 of file pid.hpp.

126 {
127 if (!std::isfinite(sp) || !std::isfinite(fb) || !std::isfinite(fb_dot) ||
128 !std::isfinite(dt))
129 {
130 return last_out_;
131 }
132
133 // Compute error
135 Scalar k_err = err * param_.k;
136
137 // Use externally provided derivative
138 Scalar d = fb_dot;
139 if (!std::isfinite(d))
140 {
141 d = 0;
142 }
143
144 // Compute PD
145 Scalar output = (k_err * param_.p) - (d * param_.d);
146
147 // Integrate if within limits
148 Scalar i_term = i_ + k_err * dt;
150
151 if (param_.i > PID_SIGMA && std::isfinite(i_term))
152 {
153 if (std::abs(output + i_out) <= param_.out_limit &&
154 std::abs(i_term) <= param_.i_limit)
155 {
156 i_ = i_term;
157 }
158 }
159
160 // Apply output limits
161 output += i_out;
163 if (std::isfinite(output) && param_.out_limit > PID_SIGMA)
164 {
165 output = std::clamp(output, -param_.out_limit, param_.out_limit);
166 }
167
168 // Store states
169 last_err_ = err;
170 last_fb_ = fb;
172 last_der_ = d;
173 return output;
174 }

◆ D()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::D ( ) const
inline

获取 D 项系数 Get derivative gain

Definition at line 196 of file pid.hpp.

196{ return param_.d; }

◆ GetFeedForward()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::GetFeedForward ( ) const
inline

获取前馈项 Get feedforward

Returns
前馈项 Feedforward

Definition at line 249 of file pid.hpp.

249{ return feed_forward_; }

◆ GetIntegralError()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::GetIntegralError ( ) const
inline

获取累计误差 Get integral error

Returns
累计误差 Integral error

Definition at line 234 of file pid.hpp.

234{ return i_; }

◆ I()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::I ( ) const
inline

获取 I 项系数 Get integral gain

Definition at line 194 of file pid.hpp.

194{ return param_.i; }

◆ ILimit()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::ILimit ( ) const
inline

获取积分限幅 Get integral limit

Definition at line 198 of file pid.hpp.

198{ return param_.i_limit; }

◆ K()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::K ( ) const
inline

获取全局比例系数 Get global proportional gain

Definition at line 190 of file pid.hpp.

190{ return param_.k; }

◆ LastDerivative()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::LastDerivative ( ) const
inline

获取上一次导数 Get last derivative

Definition at line 208 of file pid.hpp.

208{ return last_der_; }

◆ LastError()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::LastError ( ) const
inline

获取上一次误差 Get last error

Definition at line 202 of file pid.hpp.

202{ return last_err_; }

◆ LastFeedback()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::LastFeedback ( ) const
inline

获取上一次反馈值 Get last feedback

Definition at line 204 of file pid.hpp.

204{ return last_fb_; }

◆ LastOutput()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::LastOutput ( ) const
inline

获取上一次输出 Get last output

Definition at line 206 of file pid.hpp.

206{ return last_out_; }

◆ OutLimit()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::OutLimit ( ) const
inline

获取输出限幅 Get output limit

Definition at line 200 of file pid.hpp.

200{ return param_.out_limit; }

◆ P()

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::P ( ) const
inline

获取 P 项系数 Get proportional gain

Definition at line 192 of file pid.hpp.

192{ return param_.p; }

◆ Reset()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::Reset ( )
inline

重置控制器状态。 Reset all internal states.

Definition at line 214 of file pid.hpp.

215 {
216 i_ = 0;
217 last_err_ = 0;
218 last_fb_ = 0;
219 last_out_ = 0;
220 }

◆ SetD()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetD ( Scalar  d)
inline

设置 D 项系数 Set derivative gain

Definition at line 183 of file pid.hpp.

183{ param_.d = d; }

◆ SetFeedForward()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetFeedForward ( Scalar  feed_forward)
inline

设置前馈项 Set feedforward

Parameters
feed_forward前馈项 Feedforward

Definition at line 241 of file pid.hpp.

◆ SetI()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetI ( Scalar  i)
inline

设置 I 项系数 Set integral gain

Definition at line 181 of file pid.hpp.

181{ param_.i = i; }

◆ SetILimit()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetILimit ( Scalar  limit)
inline

设置积分限幅 Set integral limit

Definition at line 185 of file pid.hpp.

185{ param_.i_limit = limit; }

◆ SetIntegralError()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetIntegralError ( Scalar  err)
inline

设置累计误差 Set integral error

Parameters
err累计误差 Integral error

Definition at line 227 of file pid.hpp.

227{ i_ = err; }

◆ SetK()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetK ( Scalar  k)
inline

设置全局比例系数 Set global proportional gain

Definition at line 177 of file pid.hpp.

177{ param_.k = k; }

◆ SetOutLimit()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetOutLimit ( Scalar  limit)
inline

设置输出限幅 Set output limit

Definition at line 187 of file pid.hpp.

◆ SetP()

template<typename Scalar = DefaultScalar>
void LibXR::PID< Scalar >::SetP ( Scalar  p)
inline

设置 P 项系数 Set proportional gain

Definition at line 179 of file pid.hpp.

179{ param_.p = p; }

Field Documentation

◆ feed_forward_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::feed_forward_ = 0
private

前馈项 Feedforward term

Definition at line 258 of file pid.hpp.

◆ i_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::i_ = 0
private

积分状态 Integral state

Definition at line 253 of file pid.hpp.

◆ last_der_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::last_der_ = 0
private

上次导数 Last derivative

Definition at line 256 of file pid.hpp.

◆ last_err_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::last_err_ = 0
private

上次误差 Last error

Definition at line 254 of file pid.hpp.

◆ last_fb_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::last_fb_ = 0
private

上次反馈 Last feedback

Definition at line 255 of file pid.hpp.

◆ last_out_

template<typename Scalar = DefaultScalar>
Scalar LibXR::PID< Scalar >::last_out_ = 0
private

上次输出 Last output

Definition at line 257 of file pid.hpp.

◆ param_

template<typename Scalar = DefaultScalar>
Param LibXR::PID< Scalar >::param_
private

PID 参数 PID parameter set.

Definition at line 252 of file pid.hpp.


The documentation for this class was generated from the following file: