Skip to content

Commit beb9767

Browse files
destoglchristophfroehlichsaikishor
authored
[PID] Add support for saving i-term when PID is reset (#180)
Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 6611872 commit beb9767

File tree

7 files changed

+132
-11
lines changed

7 files changed

+132
-11
lines changed

include/control_toolbox/pid.hpp

+24-1
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,14 @@ namespace control_toolbox
5252
be subclassed to provide more specific controls
5353
based on a particular control loop.
5454
55+
This class also allows for retention of integral
56+
term on reset. This is useful for control loops
57+
that are enabled/disabled with a constant steady-state
58+
external disturbance. Once the integrator cancels
59+
out the external disturbance, disabling/resetting/
60+
re-enabling closed-loop control does not require
61+
the integrator to wind up again.
62+
5563
In particular, this class implements the standard
5664
pid equation:
5765
@@ -132,18 +140,20 @@ class Pid
132140
* \param d The derivative gain.
133141
* \param i_max The max integral windup.
134142
* \param i_min The min integral windup.
135-
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced
143+
* \param antiwindup If true, antiwindup is enabled and i_max/i_min are enforced.
136144
*
137145
* \throws An std::invalid_argument exception is thrown if i_min > i_max
138146
*/
139147
Gains(double p, double i, double d, double i_max, double i_min, bool antiwindup)
140148
: p_gain_(p), i_gain_(i), d_gain_(d), i_max_(i_max), i_min_(i_min), antiwindup_(antiwindup)
141149
{
142150
}
151+
143152
// Default constructor
144153
Gains() : p_gain_(0.0), i_gain_(0.0), d_gain_(0.0), i_max_(0.0), i_min_(0.0), antiwindup_(false)
145154
{
146155
}
156+
147157
double p_gain_; /**< Proportional gain. */
148158
double i_gain_; /**< Integral gain. */
149159
double d_gain_; /**< Derivative gain. */
@@ -198,9 +208,22 @@ class Pid
198208

199209
/*!
200210
* \brief Reset the state of this PID controller
211+
* @note The integral term is not retained and it is reset to zero
201212
*/
202213
void reset();
203214

215+
/*!
216+
* \brief Reset the state of this PID controller
217+
*
218+
* \param save_iterm boolean indicating if integral term is retained on reset()
219+
*/
220+
void reset(bool save_iterm);
221+
222+
/*!
223+
* \brief Clear the saved integrator output of this controller
224+
*/
225+
void clear_saved_iterm();
226+
204227
/*!
205228
* \brief Get PID gains for the controller.
206229
* \param p The proportional gain.

include/control_toolbox/pid_ros.hpp

+23
Original file line numberDiff line numberDiff line change
@@ -102,6 +102,21 @@ class PidROS
102102
*/
103103
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup);
104104

105+
/*!
106+
* \brief Initialize the PID controller and set the parameters
107+
* \param p The proportional gain.
108+
* \param i The integral gain.
109+
* \param d The derivative gain.
110+
* \param i_max The max integral windup.
111+
* \param i_min The min integral windup.
112+
* \param antiwindup antiwindup.
113+
* \param save_iterm save integrator output between resets.
114+
*
115+
* \note New gains are not applied if i_min_ > i_max_
116+
*/
117+
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup,
118+
bool save_iterm);
119+
105120
/*!
106121
* \brief Initialize the PID controller based on already set parameters
107122
* \return True if all parameters are set (p, i, d, i_min and i_max), False otherwise
@@ -110,9 +125,17 @@ class PidROS
110125

111126
/*!
112127
* \brief Reset the state of this PID controller
128+
* @note The integral term is not retained and it is reset to zero
113129
*/
114130
void reset();
115131

132+
/*!
133+
* \brief Reset the state of this PID controller
134+
*
135+
* \param save_iterm boolean indicating if integral term is retained on reset()
136+
*/
137+
void reset(bool save_iterm);
138+
116139
/*!
117140
* \brief Set the PID error and compute the PID command with nonuniform time
118141
* step size. The derivative error is computed from the change in the error

src/pid.cpp

+19-1
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,9 @@ Pid::Pid(double p, double i, double d, double i_max, double i_min, bool antiwind
5454
}
5555
setGains(p, i, d, i_max, i_min, antiwindup);
5656

57+
// Initialize saved i-term values
58+
clear_saved_iterm();
59+
5760
reset();
5861
}
5962

@@ -62,6 +65,9 @@ Pid::Pid(const Pid & source)
6265
// Copy the realtime buffer to the new PID class
6366
gains_buffer_ = source.gains_buffer_;
6467

68+
// Initialize saved i-term values
69+
clear_saved_iterm();
70+
6571
// Reset the state of this PID controller
6672
reset();
6773
}
@@ -76,12 +82,24 @@ void Pid::initPid(double p, double i, double d, double i_max, double i_min, bool
7682
}
7783

7884
void Pid::reset()
85+
{
86+
reset(false);
87+
}
88+
89+
void Pid::reset(bool save_iterm)
7990
{
8091
p_error_last_ = 0.0;
8192
p_error_ = 0.0;
82-
i_error_ = 0.0;
8393
d_error_ = 0.0;
8494
cmd_ = 0.0;
95+
96+
// Check to see if we should reset integral error here
97+
if (!save_iterm) clear_saved_iterm();
98+
}
99+
100+
void Pid::clear_saved_iterm()
101+
{
102+
i_error_ = 0.0;
85103
}
86104

87105
void Pid::getGains(double & p, double & i, double & d, double & i_max, double & i_min)

src/pid_ros.cpp

+19-2
Original file line numberDiff line numberDiff line change
@@ -177,6 +177,7 @@ bool PidROS::initPid()
177177
all_params_available &= getDoubleParam(param_prefix_ + "i_clamp_min", i_min);
178178

179179
getBooleanParam(param_prefix_ + "antiwindup", antiwindup);
180+
declareParam(param_prefix_ + "save_iterm", rclcpp::ParameterValue(false));
180181

181182
if (all_params_available) {
182183
setParameterEventCallback();
@@ -195,6 +196,12 @@ void PidROS::declareParam(const std::string & param_name, rclcpp::ParameterValue
195196
}
196197

197198
void PidROS::initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup)
199+
{
200+
initPid(p, i, d, i_max, i_min, antiwindup, false);
201+
}
202+
203+
void PidROS::initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup,
204+
bool save_iterm)
198205
{
199206
if (i_min > i_max) {
200207
RCLCPP_ERROR(node_logging_->get_logger(), "received i_min > i_max, skip new gains");
@@ -207,12 +214,22 @@ void PidROS::initPid(double p, double i, double d, double i_max, double i_min, b
207214
declareParam(param_prefix_ + "i_clamp_max", rclcpp::ParameterValue(i_max));
208215
declareParam(param_prefix_ + "i_clamp_min", rclcpp::ParameterValue(i_min));
209216
declareParam(param_prefix_ + "antiwindup", rclcpp::ParameterValue(antiwindup));
217+
declareParam(param_prefix_ + "save_iterm", rclcpp::ParameterValue(save_iterm));
210218

211219
setParameterEventCallback();
212220
}
213221
}
214222

215-
void PidROS::reset() { pid_.reset(); }
223+
void PidROS::reset() {
224+
bool save_iterm = false;
225+
getBooleanParam(param_prefix_ + "save_iterm", save_iterm);
226+
reset(save_iterm);
227+
}
228+
229+
void PidROS::reset(bool save_iterm)
230+
{
231+
pid_.reset(save_iterm);
232+
}
216233

217234
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> PidROS::getPidStatePublisher()
218235
{
@@ -249,7 +266,7 @@ void PidROS::setGains(double p, double i, double d, double i_max, double i_min,
249266
rclcpp::Parameter(param_prefix_ + "i_clamp_min", i_min),
250267
rclcpp::Parameter(param_prefix_ + "antiwindup", antiwindup)});
251268

252-
pid_.setGains(p, i, d, i_max, i_min, antiwindup);
269+
pid_.setGains(p, i, d, i_max, i_min, antiwindup);
253270
}
254271
}
255272

test/pid_parameters_tests.cpp

+15-5
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,9 @@ void check_set_parameters(
5757
const double I_MAX = 10.0;
5858
const double I_MIN = -10.0;
5959
const bool ANTIWINDUP = true;
60+
const bool SAVE_ITERM = true;
6061

61-
ASSERT_NO_THROW(pid.initPid(P, I, D, I_MAX, I_MIN, ANTIWINDUP));
62+
ASSERT_NO_THROW(pid.initPid(P, I, D, I_MAX, I_MIN, ANTIWINDUP, SAVE_ITERM));
6263

6364
rclcpp::Parameter param;
6465

@@ -81,6 +82,9 @@ void check_set_parameters(
8182
ASSERT_TRUE(node->get_parameter(prefix + "antiwindup", param));
8283
ASSERT_EQ(param.get_value<bool>(), ANTIWINDUP);
8384

85+
ASSERT_TRUE(node->get_parameter(prefix + "save_iterm", param));
86+
ASSERT_EQ(param.get_value<bool>(), SAVE_ITERM);
87+
8488
// check gains were set
8589
control_toolbox::Pid::Gains gains = pid.getGains();
8690
ASSERT_EQ(gains.p_gain_, P);
@@ -215,8 +219,9 @@ TEST(PidParametersTest, SetParametersTest)
215219
const double I_MAX = 10.0;
216220
const double I_MIN = -10.0;
217221
const bool ANTIWINDUP = true;
222+
const bool SAVE_ITERM = false;
218223

219-
pid.initPid(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
224+
pid.initPid(P, I, D, I_MAX, I_MIN, ANTIWINDUP, SAVE_ITERM);
220225

221226
rcl_interfaces::msg::SetParametersResult set_result;
222227

@@ -237,6 +242,8 @@ TEST(PidParametersTest, SetParametersTest)
237242
ASSERT_TRUE(set_result.successful);
238243
ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("antiwindup", ANTIWINDUP)));
239244
ASSERT_TRUE(set_result.successful);
245+
ASSERT_NO_THROW(set_result = node->set_parameter(rclcpp::Parameter("save_iterm", SAVE_ITERM)));
246+
ASSERT_TRUE(set_result.successful);
240247

241248
// process callbacks
242249
rclcpp::spin_some(node->get_node_base_interface());
@@ -314,7 +321,7 @@ TEST(PidParametersTest, GetParametersTest)
314321
const double I_MIN = -10.0;
315322
const bool ANTIWINDUP = true;
316323

317-
pid.initPid(0.0, 0.0, 0.0, 0.0, 0.0, false);
324+
pid.initPid(0.0, 0.0, 0.0, 0.0, 0.0, false, false);
318325
pid.setGains(P, I, D, I_MAX, I_MIN, ANTIWINDUP);
319326

320327
rclcpp::Parameter param;
@@ -336,6 +343,9 @@ TEST(PidParametersTest, GetParametersTest)
336343

337344
ASSERT_TRUE(node->get_parameter("antiwindup", param));
338345
ASSERT_EQ(param.get_value<bool>(), ANTIWINDUP);
346+
347+
ASSERT_TRUE(node->get_parameter("save_iterm", param));
348+
ASSERT_EQ(param.get_value<bool>(), false);
339349
}
340350

341351
TEST(PidParametersTest, GetParametersFromParams)
@@ -380,8 +390,8 @@ TEST(PidParametersTest, MultiplePidInstances)
380390
const double I_MAX = 10.0;
381391
const double I_MIN = -10.0;
382392

383-
ASSERT_NO_THROW(pid_1.initPid(P, I, D, I_MAX, I_MIN, false));
384-
ASSERT_NO_THROW(pid_2.initPid(P, I, D, I_MAX, I_MIN, true));
393+
ASSERT_NO_THROW(pid_1.initPid(P, I, D, I_MAX, I_MIN, false, false));
394+
ASSERT_NO_THROW(pid_2.initPid(P, I, D, I_MAX, I_MIN, true, false));
385395

386396
rclcpp::Parameter param_1, param_2;
387397
ASSERT_TRUE(node->get_parameter("PID_1.p", param_1));

test/pid_publisher_tests.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ TEST(PidPublisherTest, PublishTest)
3939

4040
control_toolbox::PidROS pid_ros = control_toolbox::PidROS(node);
4141

42-
pid_ros.initPid(1.0, 1.0, 1.0, 5.0, -5.0, false);
42+
pid_ros.initPid(1.0, 1.0, 1.0, 5.0, -5.0, false, false);
4343

4444
bool callback_called = false;
4545
control_msgs::msg::PidState::SharedPtr last_state_msg;
@@ -76,7 +76,7 @@ TEST(PidPublisherTest, PublishTestLifecycle)
7676
std::dynamic_pointer_cast<rclcpp_lifecycle::LifecyclePublisher<control_msgs::msg::PidState>>(
7777
pid_ros.getPidStatePublisher());
7878

79-
pid_ros.initPid(1.0, 1.0, 1.0, 5.0, -5.0, false);
79+
pid_ros.initPid(1.0, 1.0, 1.0, 5.0, -5.0, false, false);
8080

8181
bool callback_called = false;
8282
control_msgs::msg::PidState::SharedPtr last_state_msg;

test/pid_tests.cpp

+30
Original file line numberDiff line numberDiff line change
@@ -345,6 +345,36 @@ TEST(CommandTest, integralOnlyTest)
345345
cmd = pid.computeCommand(1.0, static_cast<uint64_t>(1.0 * 1e9));
346346
// Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1
347347
EXPECT_EQ(0.0, cmd);
348+
349+
// If initial error = 0, i-gain = 1, dt = 1
350+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
351+
// Then expect command = error
352+
EXPECT_EQ(-0.5, cmd);
353+
// after reset without argument (save_iterm=false)
354+
// we expect the command to be 0 if update is called error = 0
355+
pid.reset();
356+
cmd = pid.computeCommand(0.0, static_cast<uint64_t>(1.0 * 1e9));
357+
EXPECT_EQ(0.0, cmd);
358+
359+
// If initial error = 0, i-gain = 1, dt = 1
360+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
361+
// Then expect command = error
362+
EXPECT_EQ(-0.5, cmd);
363+
// after reset with argument (save_iterm=false)
364+
// we expect the command to be 0 if update is called error = 0
365+
pid.reset(false);
366+
cmd = pid.computeCommand(0.0, static_cast<uint64_t>(1.0 * 1e9));
367+
EXPECT_EQ(0.0, cmd);
368+
369+
// If initial error = 0, i-gain = 1, dt = 1
370+
cmd = pid.computeCommand(-0.5, static_cast<uint64_t>(1.0 * 1e9));
371+
// Then expect command = error
372+
EXPECT_EQ(-0.5, cmd);
373+
// after reset with save_iterm=true
374+
// we expect still the same command if update is called error = 0
375+
pid.reset(true);
376+
cmd = pid.computeCommand(0.0, static_cast<uint64_t>(1.0 * 1e9));
377+
EXPECT_EQ(-0.5, cmd);
348378
}
349379

350380
TEST(CommandTest, derivativeOnlyTest)

0 commit comments

Comments
 (0)