99
1010using 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,15 +33,17 @@ 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
41- cmd = pid.computeCommand (-1.0 , ros::Duration (1.0 ));
40+ // Test lower limit
41+ cmd = pid.computeCommand (-10.03 , ros::Duration (1.0 ));
4242 EXPECT_EQ (-1.0 , cmd);
4343
44- cmd = pid.computeCommand (-1.0 , ros::Duration (1.0 ));
45- EXPECT_EQ (-1.0 , cmd);
44+ // Test upper limit
45+ cmd = pid.computeCommand (30.0 , ros::Duration (1.0 ));
46+ EXPECT_EQ (1.0 , cmd);
4647}
4748
4849TEST (ParameterTest, integrationWindupZeroGainTest)
@@ -132,11 +133,11 @@ TEST(ParameterTest, gainSettingCopyPIDTest)
132133 EXPECT_EQ (i_min, i_min_return);
133134
134135 // Test that errors are zero
135- double pe, ie, de ;
136- pid2.getCurrentPIDErrors (&pe , &ie , &de );
137- EXPECT_EQ (0.0 , pe );
138- EXPECT_EQ (0.0 , ie );
139- EXPECT_EQ (0.0 , de );
136+ double pe2, ie2, de2 ;
137+ pid2.getCurrentPIDErrors (&pe2 , &ie2 , &de2 );
138+ EXPECT_EQ (0.0 , pe2 );
139+ EXPECT_EQ (0.0 , ie2 );
140+ EXPECT_EQ (0.0 , de2 );
140141
141142 // Test assignment constructor -------------------------------------------------
142143 Pid pid3;
@@ -151,11 +152,143 @@ TEST(ParameterTest, gainSettingCopyPIDTest)
151152 EXPECT_EQ (i_min, i_min_return);
152153
153154 // Test that errors are zero
154- double pe2, ie2, de2;
155- pid3.getCurrentPIDErrors (&pe2, &ie2, &de2);
156- EXPECT_EQ (0.0 , pe2);
157- EXPECT_EQ (0.0 , ie2);
158- EXPECT_EQ (0.0 , de2);
155+ double pe3, ie3, de3;
156+ pid3.getCurrentPIDErrors (&pe3, &ie3, &de3);
157+ EXPECT_EQ (0.0 , pe3);
158+ EXPECT_EQ (0.0 , ie3);
159+ EXPECT_EQ (0.0 , de3);
160+
161+ // Test the reset() function, it should clear errors and command
162+ pid1.reset ();
163+
164+ double pe1, ie1, de1;
165+ pid1.getCurrentPIDErrors (&pe1, &ie1, &de1);
166+ EXPECT_EQ (0.0 , pe1);
167+ EXPECT_EQ (0.0 , ie1);
168+ EXPECT_EQ (0.0 , de1);
169+
170+ double cmd1 = pid1.getCurrentCmd ();
171+ EXPECT_EQ (0.0 , cmd1);
172+ }
173+
174+ TEST (CommandTest, proportionalOnlyTest)
175+ {
176+ RecordProperty (" description" ," This test checks that a command is computed correctly using the proportional contribution only." );
177+
178+ // Set only proportional gain
179+ Pid pid (1.0 , 0.0 , 0.0 , 0.0 , 0.0 );
180+ double cmd = 0.0 ;
181+
182+ // If initial error = 0, p-gain = 1, dt = 1
183+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
184+ // Then expect command = error
185+ EXPECT_EQ (-0.5 , cmd);
186+
187+ // If call again
188+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
189+ // Then expect the same as before
190+ EXPECT_EQ (-0.5 , cmd);
191+
192+ // If call again doubling the error
193+ cmd = pid.computeCommand (-1.0 , ros::Duration (1.0 ));
194+ // Then expect the command doubl-ed
195+ EXPECT_EQ (-1.0 , cmd);
196+
197+ // If call with positive error
198+ cmd = pid.computeCommand (0.5 , ros::Duration (1.0 ));
199+ // Then expect always command = error
200+ EXPECT_EQ (0.5 , cmd);
201+ }
202+
203+ TEST (CommandTest, integralOnlyTest)
204+ {
205+ RecordProperty (" description" ," This test checks that a command is computed correctly using the integral contribution only (ATTENTION: this test depends on the integration scheme)." );
206+
207+ // Set only integral gains with enough limits to test behavior
208+ Pid pid (0.0 , 1.0 , 0.0 , 5.0 , -5.0 );
209+ double cmd = 0.0 ;
210+
211+ // If initial error = 0, i-gain = 1, dt = 1
212+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
213+ // Then expect command = error
214+ EXPECT_EQ (-0.5 , cmd);
215+
216+ // If call again with same arguments
217+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
218+ // Then expect the integration do it part doubling the command
219+ EXPECT_EQ (-1.0 , cmd);
220+
221+ // Call again with no error
222+ cmd = pid.computeCommand (0.0 , ros::Duration (1.0 ));
223+ // Expect the integral part to keep the previous command because ensure error = 0
224+ EXPECT_EQ (-1.0 , cmd);
225+
226+ // Double check that the integral contribution keep the previous command
227+ cmd = pid.computeCommand (0.0 , ros::Duration (1.0 ));
228+ EXPECT_EQ (-1.0 , cmd);
229+
230+ // Finally call again with positive error to see if the command changes in the opposite direction
231+ cmd = pid.computeCommand (1.0 , ros::Duration (1.0 ));
232+ // Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1
233+ EXPECT_EQ (0.0 , cmd);
234+ }
235+
236+ TEST (CommandTest, derivativeOnlyTest)
237+ {
238+ 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)." );
239+
240+ // Set only derivative gain
241+ Pid pid (0.0 , 0.0 , 1.0 , 0.0 , 0.0 );
242+ double cmd = 0.0 ;
243+
244+ // If initial error = 0, d-gain = 1, dt = 1
245+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
246+ // Then expect command = error
247+ EXPECT_EQ (-0.5 , cmd);
248+
249+ // If call again with same error
250+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
251+ // Then expect command = 0 due to no variation on error
252+ EXPECT_EQ (0.0 , cmd);
253+
254+ // If call again with same error and smaller control period
255+ cmd = pid.computeCommand (-0.5 , ros::Duration (0.1 ));
256+ // Then expect command = 0 again
257+ EXPECT_EQ (0.0 , cmd);
258+
259+ // If the error increases, with dt = 1
260+ cmd = pid.computeCommand (-1.0 , ros::Duration (1.0 ));
261+ // Then expect the command = change in dt
262+ EXPECT_EQ (-0.5 , cmd);
263+
264+ // If error decreases, with dt = 1
265+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
266+ // Then expect always the command = change in dt (note the sign flip)
267+ EXPECT_EQ (0.5 , cmd);
268+ }
269+
270+ TEST (CommandTest, completePIDTest)
271+ {
272+ 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)." );
273+
274+ Pid pid (1.0 , 1.0 , 1.0 , 5.0 , -5.0 );
275+ double cmd = 0.0 ;
276+
277+ // All contributions are tested, here few tests check that they sum up correctly
278+ // If initial error = 0, all gains = 1, dt = 1
279+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
280+ // Then expect command = 3x error
281+ EXPECT_EQ (-1.5 , cmd);
282+
283+ // If call again with same arguments, no error change, but integration do its part
284+ cmd = pid.computeCommand (-0.5 , ros::Duration (1.0 ));
285+ // Then expect command = 3x error againa
286+ EXPECT_EQ (-1.5 , cmd);
287+
288+ // If call again increasing the error
289+ cmd = pid.computeCommand (-1.0 , ros::Duration (1.0 ));
290+ // Then expect command equals to p = -1, i = -2.0 (i.e. - 0.5 - 0.5 - 1.0), d = -0.5
291+ EXPECT_EQ (-3.5 , cmd);
159292}
160293
161294int main (int argc, char ** argv) {
0 commit comments