Skip to content

Commit b497e3e

Browse files
committed
Increasing covergae of PID class test suite.
1 parent 06ccaed commit b497e3e

File tree

1 file changed

+152
-19
lines changed

1 file changed

+152
-19
lines changed

test/pid_tests.cpp

Lines changed: 152 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -9,17 +9,16 @@
99

1010
using namespace control_toolbox;
1111

12-
TEST(ParameterTest, zeroITermBadIBoundsTest)
12+
TEST(ParameterTest, ITermBadIBoundsTest)
1313
{
14-
RecordProperty("description","This test checks robustness against divide-by-zero errors when given integral term bounds which do not include 0.0.");
15-
16-
Pid pid(1.0, 0.0, 0.0, -1.0, 0.0);
14+
RecordProperty("description","This test checks that the integral contribution is robust to bad i_bounds specification (i.e. i_min > i_max).");
1715

16+
// Check that the output is not a non-sense if i-bounds are bad, i.e. i_min > i_max
17+
Pid pid(1.0, 1.0, 1.0, -1.0, 1.0);
1818
double cmd = 0.0;
1919
double pe,ie,de;
2020

2121
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
22-
2322
pid.getCurrentPIDErrors(&pe,&ie,&de);
2423
EXPECT_FALSE(boost::math::isinf(ie));
2524
EXPECT_FALSE(boost::math::isnan(cmd));
@@ -34,16 +33,18 @@ TEST(ParameterTest, integrationWindupTest)
3433
{
3534
RecordProperty("description","This test succeeds if the integral contribution is prevented from winding up when the integral gain is non-zero.");
3635

37-
Pid pid(0.0, 2.0, 0.0, 1.0, -1.0);
36+
Pid pid(0.0, 1.0, 0.0, 1.0, -1.0);
3837

3938
double cmd = 0.0;
4039
double pe,ie,de;
4140

42-
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
41+
// Test lower limit
42+
cmd = pid.computeCommand(-10.03, ros::Duration(1.0));
4343
EXPECT_EQ(-1.0, cmd);
4444

45-
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
46-
EXPECT_EQ(-1.0, cmd);
45+
// Test upper limit
46+
cmd = pid.computeCommand(30.0, ros::Duration(1.0));
47+
EXPECT_EQ(1.0, cmd);
4748
}
4849

4950
TEST(ParameterTest, integrationWindupZeroGainTest)
@@ -133,11 +134,11 @@ TEST(ParameterTest, gainSettingCopyPIDTest)
133134
EXPECT_EQ(i_min, i_min_return);
134135

135136
// Test that errors are zero
136-
double pe, ie, de;
137-
pid2.getCurrentPIDErrors(&pe, &ie, &de);
138-
EXPECT_EQ(0.0, pe);
139-
EXPECT_EQ(0.0, ie);
140-
EXPECT_EQ(0.0, de);
137+
double pe2, ie2, de2;
138+
pid2.getCurrentPIDErrors(&pe2, &ie2, &de2);
139+
EXPECT_EQ(0.0, pe2);
140+
EXPECT_EQ(0.0, ie2);
141+
EXPECT_EQ(0.0, de2);
141142

142143
// Test assignment constructor -------------------------------------------------
143144
Pid pid3;
@@ -152,11 +153,143 @@ TEST(ParameterTest, gainSettingCopyPIDTest)
152153
EXPECT_EQ(i_min, i_min_return);
153154

154155
// Test that errors are zero
155-
double pe2, ie2, de2;
156-
pid3.getCurrentPIDErrors(&pe2, &ie2, &de2);
157-
EXPECT_EQ(0.0, pe2);
158-
EXPECT_EQ(0.0, ie2);
159-
EXPECT_EQ(0.0, de2);
156+
double pe3, ie3, de3;
157+
pid3.getCurrentPIDErrors(&pe3, &ie3, &de3);
158+
EXPECT_EQ(0.0, pe3);
159+
EXPECT_EQ(0.0, ie3);
160+
EXPECT_EQ(0.0, de3);
161+
162+
// Test the reset() function, it should clear errors and command
163+
pid1.reset();
164+
165+
double pe1, ie1, de1;
166+
pid1.getCurrentPIDErrors(&pe1, &ie1, &de1);
167+
EXPECT_EQ(0.0, pe1);
168+
EXPECT_EQ(0.0, ie1);
169+
EXPECT_EQ(0.0, de1);
170+
171+
double cmd1 = pid1.getCurrentCmd();
172+
EXPECT_EQ(0.0, cmd1);
173+
}
174+
175+
TEST(CommandTest, proportionalOnlyTest)
176+
{
177+
RecordProperty("description","This test checks that a command is computed correctly using the proportional contribution only.");
178+
179+
// Set only proportional gain
180+
Pid pid(1.0, 0.0, 0.0, 0.0, 0.0);
181+
double cmd = 0.0;
182+
183+
// If initial error = 0, p-gain = 1, dt = 1
184+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
185+
// Then expect command = error
186+
EXPECT_EQ(-0.5, cmd);
187+
188+
// If call again
189+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
190+
// Then expect the same as before
191+
EXPECT_EQ(-0.5, cmd);
192+
193+
// If call again doubling the error
194+
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
195+
// Then expect the command doubl-ed
196+
EXPECT_EQ(-1.0, cmd);
197+
198+
// If call with positive error
199+
cmd = pid.computeCommand(0.5, ros::Duration(1.0));
200+
// Then expect always command = error
201+
EXPECT_EQ(0.5, cmd);
202+
}
203+
204+
TEST(CommandTest, integralOnlyTest)
205+
{
206+
RecordProperty("description","This test checks that a command is computed correctly using the integral contribution only (ATTENTION: this test depends on the integration scheme).");
207+
208+
// Set only integral gains with enough limits to test behavior
209+
Pid pid(0.0, 1.0, 0.0, 5.0, -5.0);
210+
double cmd = 0.0;
211+
212+
// If initial error = 0, i-gain = 1, dt = 1
213+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
214+
// Then expect command = error
215+
EXPECT_EQ(-0.5, cmd);
216+
217+
// If call again with same arguments
218+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
219+
// Then expect the integration do it part doubling the command
220+
EXPECT_EQ(-1.0, cmd);
221+
222+
// Call again with no error
223+
cmd = pid.computeCommand(0.0, ros::Duration(1.0));
224+
// Expect the integral part to keep the previous command because ensure error = 0
225+
EXPECT_EQ(-1.0, cmd);
226+
227+
// Double check that the integral contribution keep the previous command
228+
cmd = pid.computeCommand(0.0, ros::Duration(1.0));
229+
EXPECT_EQ(-1.0, cmd);
230+
231+
// Finally call again with positive error to see if the command changes in the opposite direction
232+
cmd = pid.computeCommand(1.0, ros::Duration(1.0));
233+
// Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1
234+
EXPECT_EQ(0.0, cmd);
235+
}
236+
237+
TEST(CommandTest, derivativeOnlyTest)
238+
{
239+
RecordProperty("description","This test checks that a command is computed correctly using the derivative contribution only with own differentiation (ATTENTION: this test depends on the differentiation scheme).");
240+
241+
// Set only derivative gain
242+
Pid pid(0.0, 0.0, 1.0, 0.0, 0.0);
243+
double cmd = 0.0;
244+
245+
// If initial error = 0, d-gain = 1, dt = 1
246+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
247+
// Then expect command = error
248+
EXPECT_EQ(-0.5, cmd);
249+
250+
// If call again with same error
251+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
252+
// Then expect command = 0 due to no variation on error
253+
EXPECT_EQ(0.0, cmd);
254+
255+
// If call again with same error and smaller control period
256+
cmd = pid.computeCommand(-0.5, ros::Duration(0.1));
257+
// Then expect command = 0 again
258+
EXPECT_EQ(0.0, cmd);
259+
260+
// If the error increases, with dt = 1
261+
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
262+
// Then expect the command = change in dt
263+
EXPECT_EQ(-0.5, cmd);
264+
265+
// If error decreases, with dt = 1
266+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
267+
// Then expect always the command = change in dt (note the sign flip)
268+
EXPECT_EQ(0.5, cmd);
269+
}
270+
271+
TEST(CommandTest, completePIDTest)
272+
{
273+
RecordProperty("description","This test checks that a command is computed correctly using a complete PID controller (ATTENTION: this test depends on the integral and differentiation schemes).");
274+
275+
Pid pid(1.0, 1.0, 1.0, 5.0, -5.0);
276+
double cmd = 0.0;
277+
278+
// All contributions are tested, here few tests check that they sum up correctly
279+
// If initial error = 0, all gains = 1, dt = 1
280+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
281+
// Then expect command = 3x error
282+
EXPECT_EQ(-1.5, cmd);
283+
284+
// If call again with same arguments, no error change, but integration do its part
285+
cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
286+
// Then expect command = 3x error againa
287+
EXPECT_EQ(-1.5, cmd);
288+
289+
// If call again increasing the error
290+
cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
291+
// Then expect command equals to p = -1, i = -2.0 (i.e. - 0.5 - 0.5 - 1.0), d = -0.5
292+
EXPECT_EQ(-3.5, cmd);
160293
}
161294

162295
int main(int argc, char** argv) {

0 commit comments

Comments
 (0)