Skip to content

Commit 37a12e8

Browse files
[Pid] Save i_term instead of error integral (#294)
1 parent 769d610 commit 37a12e8

File tree

5 files changed

+29
-36
lines changed

5 files changed

+29
-36
lines changed

include/control_toolbox/pid.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -400,7 +400,7 @@ class Pid
400400
/*!
401401
* \brief Return PID error terms for the controller.
402402
* \param pe The proportional error.
403-
* \param ie The integral error.
403+
* \param ie The weighted integral error.
404404
* \param de The derivative error.
405405
*/
406406
void get_current_pid_errors(double & pe, double & ie, double & de);
@@ -431,8 +431,8 @@ class Pid
431431

432432
double p_error_last_; /** Save state for derivative state calculation. */
433433
double p_error_; /** Error. */
434-
double i_error_; /** Integral of error. */
435434
double d_error_; /** Derivative of error. */
435+
double i_term_; /** Integrator state. */
436436
double cmd_; /** Command to send. */
437437
};
438438

include/control_toolbox/pid_ros.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -217,7 +217,7 @@ class PidROS
217217
/*!
218218
* \brief Return PID error terms for the controller.
219219
* \param pe[out] The proportional error.
220-
* \param ie[out] The integral error.
220+
* \param ie[out] The weighted integral error.
221221
* \param de[out] The derivative error.
222222
*/
223223
void get_current_pid_errors(double & pe, double & ie, double & de);

src/pid.cpp

Lines changed: 11 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ void Pid::reset(bool save_i_term)
9999

100100
void Pid::clear_saved_iterm()
101101
{
102-
i_error_ = 0.0;
102+
i_term_ = 0.0;
103103
}
104104

105105
void Pid::get_gains(double & p, double & i, double & d, double & i_max, double & i_min)
@@ -182,7 +182,7 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s)
182182
// Get the gain parameters from the realtime buffer
183183
Gains gains = *gains_buffer_.readFromRT();
184184

185-
double p_term, d_term, i_term;
185+
double p_term, d_term;
186186
p_error_ = error; // this is error = target - state
187187
d_error_ = error_dot;
188188

@@ -194,29 +194,21 @@ double Pid::compute_command(double error, double error_dot, const double & dt_s)
194194
// Calculate proportional contribution to command
195195
p_term = gains.p_gain_ * p_error_;
196196

197-
// Calculate the integral of the position error
198-
i_error_ += dt_s * p_error_;
199-
200-
if (gains.antiwindup_ && gains.i_gain_ != 0) {
201-
// Prevent i_error_ from climbing higher than permitted by i_max_/i_min_
202-
std::pair<double, double> bounds =
203-
std::minmax<double>(gains.i_min_ / gains.i_gain_, gains.i_max_ / gains.i_gain_);
204-
i_error_ = std::clamp(i_error_, bounds.first, bounds.second);
205-
}
206-
207197
// Calculate integral contribution to command
208-
i_term = gains.i_gain_ * i_error_;
209-
210-
if (!gains.antiwindup_) {
211-
// Limit i_term so that the limit is meaningful in the output
212-
i_term = std::clamp(i_term, gains.i_min_, gains.i_max_);
198+
if (gains.antiwindup_) {
199+
// Prevent i_term_ from climbing higher than permitted by i_max_/i_min_
200+
i_term_ = std::clamp(i_term_ + gains.i_gain_ * dt_s * p_error_,
201+
gains.i_min_, gains.i_max_);
202+
} else {
203+
i_term_ += gains.i_gain_ * dt_s * p_error_;
213204
}
214205

215206
// Calculate derivative contribution to command
216207
d_term = gains.d_gain_ * d_error_;
217208

218209
// Compute the command
219-
cmd_ = p_term + i_term + d_term;
210+
// Limit i_term so that the limit is meaningful in the output
211+
cmd_ = p_term + std::clamp(i_term_, gains.i_min_, gains.i_max_) + d_term;
220212

221213
return cmd_;
222214
}
@@ -228,7 +220,7 @@ double Pid::get_current_cmd() { return cmd_; }
228220
void Pid::get_current_pid_errors(double & pe, double & ie, double & de)
229221
{
230222
pe = p_error_;
231-
ie = i_error_;
223+
ie = i_term_;
232224
de = d_error_;
233225
}
234226

src/pid_ros.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -273,8 +273,8 @@ void PidROS::publish_pid_state(double cmd, double error, rclcpp::Duration dt)
273273
{
274274
Pid::Gains gains = pid_.get_gains();
275275

276-
double p_error, i_error, d_error;
277-
get_current_pid_errors(p_error, i_error, d_error);
276+
double p_error, i_term, d_error;
277+
get_current_pid_errors(p_error, i_term, d_error);
278278

279279
// Publish controller state if configured
280280
if (rt_state_pub_) {
@@ -284,7 +284,7 @@ void PidROS::publish_pid_state(double cmd, double error, rclcpp::Duration dt)
284284
rt_state_pub_->msg_.error = error;
285285
rt_state_pub_->msg_.error_dot = d_error;
286286
rt_state_pub_->msg_.p_error = p_error;
287-
rt_state_pub_->msg_.i_error = i_error;
287+
rt_state_pub_->msg_.i_error = i_term;
288288
rt_state_pub_->msg_.d_error = d_error;
289289
rt_state_pub_->msg_.p_term = gains.p_gain_;
290290
rt_state_pub_->msg_.i_term = gains.i_gain_;
@@ -314,8 +314,8 @@ void PidROS::print_values()
314314
{
315315
Pid::Gains gains = pid_.get_gains();
316316

317-
double p_error, i_error, d_error;
318-
get_current_pid_errors(p_error, i_error, d_error);
317+
double p_error, i_term, d_error;
318+
get_current_pid_errors(p_error, i_term, d_error);
319319

320320
RCLCPP_INFO_STREAM(node_logging_->get_logger(), "Current Values of PID template:\n"
321321
<< " P Gain: " << gains.p_gain_ << "\n"
@@ -326,7 +326,7 @@ void PidROS::print_values()
326326
<< " Antiwindup: " << gains.antiwindup_
327327
<< "\n"
328328
<< " P_Error: " << p_error << "\n"
329-
<< " I_Error: " << i_error << "\n"
329+
<< " i_term: " << i_term << "\n"
330330
<< " D_Error: " << d_error << "\n"
331331
<< " Command: " << get_current_cmd(););
332332
}

test/pid_tests.cpp

Lines changed: 9 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -117,6 +117,7 @@ TEST(ParameterTest, integrationClampZeroGainTest)
117117
EXPECT_EQ(0.0, cmd);
118118
}
119119

120+
constexpr double EPS = 1e-9;
120121
TEST(ParameterTest, integrationAntiwindupTest)
121122
{
122123
RecordProperty(
@@ -131,16 +132,16 @@ TEST(ParameterTest, integrationAntiwindupTest)
131132
double cmd = 0.0;
132133

133134
cmd = pid.compute_command(-1.0, 1.0);
134-
EXPECT_EQ(-1.0, cmd);
135+
EXPECT_NEAR(-1.0, cmd, EPS);
135136

136137
cmd = pid.compute_command(-1.0, 1.0);
137-
EXPECT_EQ(-1.0, cmd);
138+
EXPECT_NEAR(-1.0, cmd, EPS);
138139

139140
cmd = pid.compute_command(0.5, 1.0);
140-
EXPECT_EQ(0.0, cmd);
141+
EXPECT_NEAR(0.0, cmd, EPS);
141142

142143
cmd = pid.compute_command(-1.0, 1.0);
143-
EXPECT_EQ(-1.0, cmd);
144+
EXPECT_NEAR(-1.0, cmd, EPS);
144145
}
145146

146147
TEST(ParameterTest, negativeIntegrationAntiwindupTest)
@@ -157,16 +158,16 @@ TEST(ParameterTest, negativeIntegrationAntiwindupTest)
157158
double cmd = 0.0;
158159

159160
cmd = pid.compute_command(0.1, 1.0);
160-
EXPECT_EQ(-0.2, cmd);
161+
EXPECT_NEAR(-0.2, cmd, EPS);
161162

162163
cmd = pid.compute_command(0.1, 1.0);
163-
EXPECT_EQ(-0.2, cmd);
164+
EXPECT_NEAR(-0.2, cmd, EPS);
164165

165166
cmd = pid.compute_command(-0.05, 1.0);
166-
EXPECT_EQ(-0.075, cmd);
167+
EXPECT_NEAR(-0.075, cmd, EPS);
167168

168169
cmd = pid.compute_command(0.1, 1.0);
169-
EXPECT_EQ(-0.2, cmd);
170+
EXPECT_NEAR(-0.2, cmd, EPS);
170171
}
171172

172173
TEST(ParameterTest, gainSettingCopyPIDTest)

0 commit comments

Comments
 (0)