pid_tests.cpp
Go to the documentation of this file.
00001 
00002 #include <ros/ros.h>
00003 
00004 #include <gtest/gtest.h>
00005 
00006 #include <control_toolbox/pid.h>
00007 
00008 #include <boost/math/special_functions/fpclassify.hpp>
00009 
00010 using namespace control_toolbox;
00011 
00012 TEST(ParameterTest, ITermBadIBoundsTest)
00013 {
00014   RecordProperty("description","This test checks that the integral contribution is robust to bad i_bounds specification (i.e. i_min > i_max).");
00015 
00016   // Check that the output is not a non-sense if i-bounds are bad, i.e. i_min > i_max
00017   Pid pid(1.0, 1.0, 1.0, -1.0, 1.0);
00018   double cmd = 0.0;
00019   double pe,ie,de;
00020 
00021   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00022   pid.getCurrentPIDErrors(&pe,&ie,&de);
00023   EXPECT_FALSE(boost::math::isinf(ie));
00024   EXPECT_FALSE(boost::math::isnan(cmd));
00025 
00026   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00027   pid.getCurrentPIDErrors(&pe,&ie,&de);
00028   EXPECT_FALSE(boost::math::isinf(ie));
00029   EXPECT_FALSE(boost::math::isnan(cmd));
00030 }
00031 
00032 TEST(ParameterTest, integrationWindupTest)
00033 {
00034   RecordProperty("description","This test succeeds if the integral contribution is prevented from winding up when the integral gain is non-zero.");
00035 
00036   Pid pid(0.0, 1.0, 0.0, 1.0, -1.0);
00037 
00038   double cmd = 0.0;
00039 
00040   // Test lower limit
00041   cmd = pid.computeCommand(-10.03, ros::Duration(1.0));
00042   EXPECT_EQ(-1.0, cmd);
00043 
00044   // Test upper limit
00045   cmd = pid.computeCommand(30.0, ros::Duration(1.0));
00046   EXPECT_EQ(1.0, cmd);
00047 }
00048 
00049 TEST(ParameterTest, integrationWindupZeroGainTest)
00050 {
00051   RecordProperty("description","This test succeeds if the integral contribution is prevented from winding up when the integral gain is zero. If the integral contribution is allowed to wind up while it is disabled, it can cause sudden jumps to the minimum or maximum bound in control command when re-enabled.");
00052 
00053   double i_gain = 0.0;
00054   double i_min = -1.0;
00055   double i_max = 1.0;
00056   Pid pid(0.0, i_gain, 0.0, i_max, i_min);
00057 
00058   double cmd = 0.0;
00059   double pe,ie,de;
00060 
00061   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00062   pid.getCurrentPIDErrors(&pe,&ie,&de);
00063   EXPECT_LE(i_min, cmd);
00064   EXPECT_LE(cmd, i_max);
00065   EXPECT_EQ(0.0, cmd);
00066 
00067   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00068   EXPECT_LE(i_min, cmd);
00069   EXPECT_LE(cmd, i_max);
00070   EXPECT_EQ(0.0, cmd);
00071 }
00072 
00073 TEST(ParameterTest, gainSettingCopyPIDTest)
00074 {
00075   RecordProperty("description","This test succeeds if a PID object has its gain set at different points in time then the values are get-ed and still remain the same, as well as when PID is copied.");
00076 
00077   // Test values
00078   double p_gain = rand() % 100;
00079   double i_gain = rand() % 100;
00080   double d_gain = rand() % 100;
00081   double i_max = rand() % 100;
00082   double i_min = -1 * rand() % 100;
00083 
00084   // Initialize the default way
00085   Pid pid1(p_gain, i_gain, d_gain, i_max, i_min);
00086   
00087   // Test return values  -------------------------------------------------
00088   double p_gain_return, i_gain_return, d_gain_return, i_max_return, i_min_return;
00089   pid1.getGains(p_gain_return, i_gain_return, d_gain_return, i_max_return, i_min_return);
00090 
00091   EXPECT_EQ(p_gain, p_gain_return);
00092   EXPECT_EQ(i_gain, i_gain_return);
00093   EXPECT_EQ(d_gain, d_gain_return);
00094   EXPECT_EQ(i_max, i_max_return);
00095   EXPECT_EQ(i_min, i_min_return);
00096 
00097   // Test return values using struct -------------------------------------------------
00098 
00099   // New values
00100   p_gain = rand() % 100;
00101   i_gain = rand() % 100;
00102   d_gain = rand() % 100;
00103   i_max = rand() % 100;
00104   i_min = -1 * rand() % 100;
00105   pid1.setGains(p_gain, i_gain, d_gain, i_max, i_min);
00106 
00107   Pid::Gains g1 = pid1.getGains();
00108   EXPECT_EQ(p_gain, g1.p_gain_);
00109   EXPECT_EQ(i_gain, g1.i_gain_);
00110   EXPECT_EQ(d_gain, g1.d_gain_);
00111   EXPECT_EQ(i_max, g1.i_max_);
00112   EXPECT_EQ(i_min, g1.i_min_);
00113 
00114   // \todo test initParam() -------------------------------------------------
00115   
00116 
00117   // \todo test bool init(const ros::NodeHandle &n); -----------------------------------
00118 
00119 
00120   // Send update command to populate errors -------------------------------------------------
00121   pid1.setCurrentCmd(10);
00122   pid1.computeCommand(20, ros::Duration(1.0));
00123 
00124   // Test copy constructor -------------------------------------------------
00125   Pid pid2(pid1);
00126 
00127   pid2.getGains(p_gain_return, i_gain_return, d_gain_return, i_max_return, i_min_return);
00128 
00129   EXPECT_EQ(p_gain, p_gain_return);
00130   EXPECT_EQ(i_gain, i_gain_return);
00131   EXPECT_EQ(d_gain, d_gain_return);
00132   EXPECT_EQ(i_max, i_max_return);
00133   EXPECT_EQ(i_min, i_min_return);
00134 
00135   // Test that errors are zero
00136   double pe2, ie2, de2;
00137   pid2.getCurrentPIDErrors(&pe2, &ie2, &de2);
00138   EXPECT_EQ(0.0, pe2);
00139   EXPECT_EQ(0.0, ie2);
00140   EXPECT_EQ(0.0, de2);
00141     
00142   // Test assignment constructor -------------------------------------------------
00143   Pid pid3;
00144   pid3 = pid1;
00145 
00146   pid3.getGains(p_gain_return, i_gain_return, d_gain_return, i_max_return, i_min_return);
00147 
00148   EXPECT_EQ(p_gain, p_gain_return);
00149   EXPECT_EQ(i_gain, i_gain_return);
00150   EXPECT_EQ(d_gain, d_gain_return);
00151   EXPECT_EQ(i_max, i_max_return);
00152   EXPECT_EQ(i_min, i_min_return);
00153 
00154   // Test that errors are zero
00155   double pe3, ie3, de3;
00156   pid3.getCurrentPIDErrors(&pe3, &ie3, &de3);
00157   EXPECT_EQ(0.0, pe3);
00158   EXPECT_EQ(0.0, ie3);
00159   EXPECT_EQ(0.0, de3);
00160 
00161   // Test the reset() function, it should clear errors and command
00162   pid1.reset();
00163 
00164   double pe1, ie1, de1;
00165   pid1.getCurrentPIDErrors(&pe1, &ie1, &de1);
00166   EXPECT_EQ(0.0, pe1);
00167   EXPECT_EQ(0.0, ie1);
00168   EXPECT_EQ(0.0, de1);
00169 
00170   double cmd1 = pid1.getCurrentCmd();
00171   EXPECT_EQ(0.0, cmd1);
00172 }
00173 
00174 TEST(CommandTest, proportionalOnlyTest)
00175 {
00176   RecordProperty("description","This test checks that a command is computed correctly using the proportional contribution only.");
00177 
00178   // Set only proportional gain
00179   Pid pid(1.0, 0.0, 0.0, 0.0, 0.0);
00180   double cmd = 0.0;
00181 
00182   // If initial error = 0, p-gain = 1, dt = 1
00183   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00184   // Then expect command = error
00185   EXPECT_EQ(-0.5, cmd);
00186 
00187   // If call again
00188   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00189   // Then expect the same as before
00190   EXPECT_EQ(-0.5, cmd);
00191 
00192   // If call again doubling the error
00193   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00194   // Then expect the command doubled
00195   EXPECT_EQ(-1.0, cmd);
00196 
00197   // If call with positive error
00198   cmd = pid.computeCommand(0.5, ros::Duration(1.0));
00199   // Then expect always command = error
00200   EXPECT_EQ(0.5, cmd);
00201 }
00202 
00203 TEST(CommandTest, integralOnlyTest)
00204 {
00205   RecordProperty("description","This test checks that a command is computed correctly using the integral contribution only (ATTENTION: this test depends on the integration scheme).");
00206 
00207   // Set only integral gains with enough limits to test behavior
00208   Pid pid(0.0, 1.0, 0.0, 5.0, -5.0);
00209   double cmd = 0.0;
00210 
00211   // If initial error = 0, i-gain = 1, dt = 1
00212   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00213   // Then expect command = error
00214   EXPECT_EQ(-0.5, cmd);
00215 
00216   // If call again with same arguments
00217   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00218   // Then expect the integral part to double the command
00219   EXPECT_EQ(-1.0, cmd);
00220 
00221   // Call again with no error
00222   cmd = pid.computeCommand(0.0, ros::Duration(1.0));
00223   // Expect the integral part to keep the previous command because it ensures error = 0
00224   EXPECT_EQ(-1.0, cmd);
00225 
00226   // Double check that the integral contribution keep the previous command
00227   cmd = pid.computeCommand(0.0, ros::Duration(1.0));
00228   EXPECT_EQ(-1.0, cmd);
00229 
00230   // Finally call again with positive error to see if the command changes in the opposite direction
00231   cmd = pid.computeCommand(1.0, ros::Duration(1.0));
00232   // Expect that the command is cleared since error = -1 * previous command, i-gain = 1, dt = 1
00233   EXPECT_EQ(0.0, cmd);
00234 }
00235 
00236 TEST(CommandTest, derivativeOnlyTest)
00237 {
00238   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).");
00239 
00240   // Set only derivative gain
00241   Pid pid(0.0, 0.0, 1.0, 0.0, 0.0);
00242   double cmd = 0.0;
00243 
00244   // If initial error = 0, d-gain = 1, dt = 1
00245   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00246   // Then expect command = error
00247   EXPECT_EQ(-0.5, cmd);
00248 
00249   // If call again with same error
00250   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00251   // Then expect command = 0 due to no variation on error
00252   EXPECT_EQ(0.0, cmd);
00253 
00254   // If call again with same error and smaller control period
00255   cmd = pid.computeCommand(-0.5, ros::Duration(0.1));
00256   // Then expect command = 0 again
00257   EXPECT_EQ(0.0, cmd);
00258 
00259   // If the error increases,  with dt = 1
00260   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00261   // Then expect the command = change in dt
00262   EXPECT_EQ(-0.5, cmd);
00263 
00264   // If error decreases, with dt = 1
00265   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00266   // Then expect always the command = change in dt (note the sign flip)
00267   EXPECT_EQ(0.5, cmd);
00268 }
00269 
00270 TEST(CommandTest, completePIDTest)
00271 {
00272   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).");
00273 
00274   Pid pid(1.0, 1.0, 1.0, 5.0, -5.0);
00275   double cmd = 0.0;
00276 
00277   // All contributions are tested, here few tests check that they sum up correctly
00278   // If initial error = 0, all gains = 1, dt = 1
00279   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00280   // Then expect command = 3x error
00281   EXPECT_EQ(-1.5, cmd);
00282 
00283   // If call again with same arguments, no error change, but integration do its part
00284   cmd = pid.computeCommand(-0.5, ros::Duration(1.0));
00285   // Then expect command = 3x error again
00286   EXPECT_EQ(-1.5, cmd);
00287 
00288   // If call again increasing the error
00289   cmd = pid.computeCommand(-1.0, ros::Duration(1.0));
00290   // Then expect command equals to p = -1, i = -2.0 (i.e. - 0.5 - 0.5 - 1.0), d = -0.5
00291   EXPECT_EQ(-3.5, cmd);
00292 }
00293 
00294 int main(int argc, char** argv) {
00295   testing::InitGoogleTest(&argc, argv);
00296   return RUN_ALL_TESTS();
00297 }


control_toolbox
Author(s): Melonee Wise, Sachin Chitta, John Hsu
autogenerated on Fri Apr 15 2016 15:39:29