00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <vector>
00031
00032 #include <gtest/gtest.h>
00033 #include <ros/time.h>
00034 #include <sys/time.h>
00035
00036 using namespace ros;
00037
00039
00040 double epsilon = 1e-9;
00041
00042 void seed_rand()
00043 {
00044
00045 timeval temp_time_struct;
00046 gettimeofday(&temp_time_struct,NULL);
00047 srand(temp_time_struct.tv_usec);
00048 };
00049
00050 void generate_rand_times(uint32_t range, uint64_t runs, std::vector<ros::Time>& values1, std::vector<ros::Time>& values2)
00051 {
00052 seed_rand();
00053 values1.clear();
00054 values2.clear();
00055 values1.reserve(runs);
00056 values2.reserve(runs);
00057 for ( uint32_t i = 0; i < runs ; i++ )
00058 {
00059 values1.push_back(ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
00060 values2.push_back(ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
00061 }
00062 }
00063
00064 void generate_rand_durations(uint32_t range, uint64_t runs, std::vector<ros::Duration>& values1, std::vector<ros::Duration>& values2)
00065 {
00066 seed_rand();
00067 values1.clear();
00068 values2.clear();
00069 values1.reserve(runs);
00070 values2.reserve(runs);
00071 for ( uint32_t i = 0; i < runs ; i++ )
00072 {
00073 values1.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
00074 values2.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
00075 }
00076 }
00077
00078 TEST(Time, size)
00079 {
00080 ASSERT_EQ(sizeof(Time), 8);
00081 ASSERT_EQ(sizeof(Duration), 8);
00082 }
00083
00084 TEST(Time, Comparitors)
00085 {
00086 std::vector<ros::Time> v1;
00087 std::vector<ros::Time> v2;
00088 generate_rand_times(100, 1000, v1,v2);
00089
00090 for (uint32_t i = 0; i < v1.size(); i++)
00091 {
00092 if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
00093 {
00094 EXPECT_LT(v1[i], v2[i]);
00095
00096
00097 EXPECT_LE(v1[i], v2[i]);
00098 EXPECT_NE(v1[i], v2[i]);
00099 }
00100 else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
00101 {
00102 EXPECT_GT(v1[i], v2[i]);
00103 EXPECT_GE(v1[i], v2[i]);
00104 EXPECT_NE(v1[i], v2[i]);
00105 }
00106 else
00107 {
00108 EXPECT_EQ(v1[i], v2[i]);
00109 EXPECT_LE(v1[i], v2[i]);
00110 EXPECT_GE(v1[i], v2[i]);
00111 }
00112
00113 }
00114
00115 }
00116
00117 TEST(Time, ToFromDouble)
00118 {
00119 std::vector<ros::Time> v1;
00120 std::vector<ros::Time> v2;
00121 generate_rand_times(100, 1000, v1,v2);
00122
00123 for (uint32_t i = 0; i < v1.size(); i++)
00124 {
00125 EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
00126
00127 }
00128
00129 }
00130
00131 TEST(Time, OperatorPlus)
00132 {
00133 Time t(100, 0);
00134 Duration d(100, 0);
00135 Time r = t + d;
00136 EXPECT_EQ(r.sec, 200UL);
00137 EXPECT_EQ(r.nsec, 0UL);
00138
00139 t = Time(0, 100000UL);
00140 d = Duration(0, 100UL);
00141 r = t + d;
00142 EXPECT_EQ(r.sec, 0UL);
00143 EXPECT_EQ(r.nsec, 100100UL);
00144
00145 t = Time(0, 0);
00146 d = Duration(10, 2000003000UL);
00147 r = t + d;
00148 EXPECT_EQ(r.sec, 12UL);
00149 EXPECT_EQ(r.nsec, 3000UL);
00150 }
00151
00152 TEST(Time, OperatorMinus)
00153 {
00154 Time t(100, 0);
00155 Duration d(100, 0);
00156 Time r = t - d;
00157 EXPECT_EQ(r.sec, 0UL);
00158 EXPECT_EQ(r.nsec, 0UL);
00159
00160 t = Time(0, 100000UL);
00161 d = Duration(0, 100UL);
00162 r = t - d;
00163 EXPECT_EQ(r.sec, 0UL);
00164 EXPECT_EQ(r.nsec, 99900UL);
00165
00166 t = Time(30, 0);
00167 d = Duration(10, 2000003000UL);
00168 r = t - d;
00169 EXPECT_EQ(r.sec, 17UL);
00170 EXPECT_EQ(r.nsec, 999997000ULL);
00171 }
00172
00173 TEST(Time, OperatorPlusEquals)
00174 {
00175 Time t(100, 0);
00176 Duration d(100, 0);
00177 t += d;
00178 EXPECT_EQ(t.sec, 200UL);
00179 EXPECT_EQ(t.nsec, 0UL);
00180
00181 t = Time(0, 100000UL);
00182 d = Duration(0, 100UL);
00183 t += d;
00184 EXPECT_EQ(t.sec, 0UL);
00185 EXPECT_EQ(t.nsec, 100100UL);
00186
00187 t = Time(0, 0);
00188 d = Duration(10, 2000003000UL);
00189 t += d;
00190 EXPECT_EQ(t.sec, 12UL);
00191 EXPECT_EQ(t.nsec, 3000UL);
00192 }
00193
00194 TEST(Time, OperatorMinusEquals)
00195 {
00196 Time t(100, 0);
00197 Duration d(100, 0);
00198 t -= d;
00199 EXPECT_EQ(t.sec, 0UL);
00200 EXPECT_EQ(t.nsec, 0UL);
00201
00202 t = Time(0, 100000UL);
00203 d = Duration(0, 100UL);
00204 t -= d;
00205 EXPECT_EQ(t.sec, 0UL);
00206 EXPECT_EQ(t.nsec, 99900UL);
00207
00208 t = Time(30, 0);
00209 d = Duration(10, 2000003000UL);
00210 t -= d;
00211 EXPECT_EQ(t.sec, 17UL);
00212 EXPECT_EQ(t.nsec, 999997000ULL);
00213 }
00214
00215 TEST(Time, SecNSecConstructor)
00216 {
00217 Time t(100, 2000003000UL);
00218 EXPECT_EQ(t.sec, 102UL);
00219 EXPECT_EQ(t.nsec, 3000UL);
00220 }
00221
00222
00223
00224 TEST(Duration, Comparitors)
00225 {
00226 std::vector<ros::Duration> v1;
00227 std::vector<ros::Duration> v2;
00228 generate_rand_durations(100, 1000, v1,v2);
00229
00230 for (uint32_t i = 0; i < v1.size(); i++)
00231 {
00232 if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
00233 {
00234 EXPECT_LT(v1[i], v2[i]);
00235
00236
00237 EXPECT_LE(v1[i], v2[i]);
00238 EXPECT_NE(v1[i], v2[i]);
00239 }
00240 else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
00241 {
00242 EXPECT_GT(v1[i], v2[i]);
00243 EXPECT_GE(v1[i], v2[i]);
00244 EXPECT_NE(v1[i], v2[i]);
00245 }
00246 else
00247 {
00248 EXPECT_EQ(v1[i], v2[i]);
00249 EXPECT_LE(v1[i], v2[i]);
00250 EXPECT_GE(v1[i], v2[i]);
00251 }
00252
00253 }
00254
00255 }
00256
00257 TEST(Duration, ToFromSec)
00258 {
00259 std::vector<ros::Duration> v1;
00260 std::vector<ros::Duration> v2;
00261 generate_rand_durations(100, 1000, v1,v2);
00262
00263 for (uint32_t i = 0; i < v1.size(); i++)
00264 {
00265 EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
00266
00267 }
00268
00269 }
00270
00271
00272 TEST(Duration, OperatorPlus)
00273 {
00274 std::vector<ros::Duration> v1;
00275 std::vector<ros::Duration> v2;
00276 generate_rand_durations(100, 1000, v1,v2);
00277
00278 for (uint32_t i = 0; i < v1.size(); i++)
00279 {
00280 EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (v1[i] + v2[i]).toSec(), epsilon);
00281 ros::Duration temp = v1[i];
00282 EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (temp += v2[i]).toSec(), epsilon);
00283
00284 }
00285
00286 }
00287
00288 TEST(Duration, OperatorMinus)
00289 {
00290 std::vector<ros::Duration> v1;
00291 std::vector<ros::Duration> v2;
00292 generate_rand_durations(100, 1000, v1,v2);
00293
00294 for (uint32_t i = 0; i < v1.size(); i++)
00295 {
00296 EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (v1[i] - v2[i]).toSec(), epsilon);
00297 ros::Duration temp = v1[i];
00298 EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (temp -= v2[i]).toSec(), epsilon);
00299
00300 EXPECT_NEAR(- v2[i].toSec(), (-v2[i]).toSec(), epsilon);
00301
00302 }
00303
00304 }
00305
00306 TEST(Duration, OperatorTimes)
00307 {
00308 std::vector<ros::Duration> v1;
00309 std::vector<ros::Duration> v2;
00310 generate_rand_durations(100, 1000, v1,v2);
00311
00312 for (uint32_t i = 0; i < v1.size(); i++)
00313 {
00314 EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (v1[i] * v2[i].toSec()).toSec(), epsilon);
00315 ros::Duration temp = v1[i];
00316 EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (temp *= v2[i].toSec()).toSec(), epsilon);
00317
00318 }
00319
00320 }
00321
00322 TEST(Duration, OperatorPlusEquals)
00323 {
00324 Duration t(100, 0);
00325 Duration d(100, 0);
00326 t += d;
00327 EXPECT_EQ(t.sec, 200L);
00328 EXPECT_EQ(t.nsec, 0L);
00329
00330 t = Duration(0, 100000L);
00331 d = Duration(0, 100L);
00332 t += d;
00333 EXPECT_EQ(t.sec, 0L);
00334 EXPECT_EQ(t.nsec, 100100L);
00335
00336 t = Duration(0, 0);
00337 d = Duration(10, 2000003000L);
00338 t += d;
00339 EXPECT_EQ(t.sec, 12L);
00340 EXPECT_EQ(t.nsec, 3000L);
00341 }
00342
00343 TEST(Duration, OperatorMinusEquals)
00344 {
00345 Duration t(100, 0);
00346 Duration d(100, 0);
00347 t -= d;
00348 EXPECT_EQ(t.sec, 0L);
00349 EXPECT_EQ(t.nsec, 0L);
00350
00351 t = Duration(0, 100000L);
00352 d = Duration(0, 100L);
00353 t -= d;
00354 EXPECT_EQ(t.sec, 0L);
00355 EXPECT_EQ(t.nsec, 99900L);
00356
00357 t = Duration(30, 0);
00358 d = Duration(10, 2000003000L);
00359 t -= d;
00360 EXPECT_EQ(t.sec, 17L);
00361 EXPECT_EQ(t.nsec, 999997000L);
00362 }
00363
00364 void alarmHandler(int sig)
00365 {
00366
00367 }
00368
00369 TEST(Duration, sleepWithSignal)
00370 {
00371 signal(SIGALRM, alarmHandler);
00372 alarm(1);
00373 Time start = Time::now();
00374 Duration d(2.0);
00375 d.sleep();
00376 Time end = Time::now();
00377
00378 ASSERT_GT(end - start, d);
00379 }
00380
00382
00384
00385
00386 int main(int argc, char **argv){
00387 testing::InitGoogleTest(&argc, argv);
00388 ros::Time::init();
00389 return RUN_ALL_TESTS();
00390 }