32 #include <gtest/gtest.h>
40 #include <boost/date_time/posix_time/ptime.hpp>
52 timeval temp_time_struct;
53 gettimeofday(&temp_time_struct,NULL);
54 srand(temp_time_struct.tv_usec);
60 void generate_rand_times(uint32_t range, uint64_t runs, std::vector<ros::Time>& values1, std::vector<ros::Time>& values2)
65 values1.reserve(runs);
66 values2.reserve(runs);
67 for ( uint32_t i = 0; i < runs ; i++ )
69 values1.push_back(
ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
70 values2.push_back(
ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
74 void generate_rand_durations(uint32_t range, uint64_t runs, std::vector<ros::Duration>& values1, std::vector<ros::Duration>& values2)
79 values1.reserve(runs * 4);
80 values2.reserve(runs * 4);
81 for ( uint32_t i = 0; i < runs ; i++ )
84 values1.push_back(
ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
85 values2.push_back(
ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
90 values1.push_back(
ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
91 values2.push_back(
ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
96 values1.push_back(
ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
97 values2.push_back(
ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
102 values1.push_back(
ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
103 values2.push_back(
ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
111 ASSERT_EQ(
sizeof(
Time), 8);
117 std::vector<ros::Time> v1;
118 std::vector<ros::Time> v2;
121 for (uint32_t i = 0; i < v1.size(); i++)
123 if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
125 EXPECT_LT(v1[i], v2[i]);
128 EXPECT_LE(v1[i], v2[i]);
129 EXPECT_NE(v1[i], v2[i]);
131 else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
133 EXPECT_GT(v1[i], v2[i]);
134 EXPECT_GE(v1[i], v2[i]);
135 EXPECT_NE(v1[i], v2[i]);
139 EXPECT_EQ(v1[i], v2[i]);
140 EXPECT_LE(v1[i], v2[i]);
141 EXPECT_GE(v1[i], v2[i]);
150 std::vector<ros::Time> v1;
151 std::vector<ros::Time> v2;
154 for (uint32_t i = 0; i < v1.size(); i++)
156 EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
164 double someInt = 1031.0;
165 double t = std::nextafter(someInt, 0);
173 EXPECT_EQ(exampleTime.
sec, 1031);
174 EXPECT_EQ(exampleTime.
nsec, 0);
182 EXPECT_EQ(r.
sec, 200UL);
183 EXPECT_EQ(r.
nsec, 0UL);
185 t =
Time(0, 100000UL);
188 EXPECT_EQ(r.
sec, 0UL);
189 EXPECT_EQ(r.
nsec, 100100UL);
194 EXPECT_EQ(r.
sec, 12UL);
195 EXPECT_EQ(r.
nsec, 3000UL);
203 EXPECT_EQ(r.
sec, 0UL);
204 EXPECT_EQ(r.
nsec, 0UL);
206 t =
Time(0, 100000UL);
209 EXPECT_EQ(r.
sec, 0UL);
210 EXPECT_EQ(r.
nsec, 99900UL);
215 EXPECT_EQ(r.
sec, 17UL);
216 EXPECT_EQ(r.
nsec, 999997000ULL);
224 EXPECT_EQ(t.
sec, 200UL);
225 EXPECT_EQ(t.
nsec, 0UL);
227 t =
Time(0, 100000UL);
230 EXPECT_EQ(t.
sec, 0UL);
231 EXPECT_EQ(t.
nsec, 100100UL);
236 EXPECT_EQ(t.
sec, 12UL);
237 EXPECT_EQ(t.
nsec, 3000UL);
245 EXPECT_EQ(t.
sec, 0UL);
246 EXPECT_EQ(t.
nsec, 0UL);
248 t =
Time(0, 100000UL);
251 EXPECT_EQ(t.
sec, 0UL);
252 EXPECT_EQ(t.
nsec, 99900UL);
257 EXPECT_EQ(t.
sec, 17UL);
258 EXPECT_EQ(t.
nsec, 999997000ULL);
263 Time t(100, 2000003000UL);
264 EXPECT_EQ(t.
sec, 102UL);
265 EXPECT_EQ(t.
nsec, 3000UL);
270 std::ostringstream oss;
271 Time t(100, 2000003000UL);
272 oss << std::setfill(
'N');
273 oss << std::setw(13);
276 EXPECT_EQ(oss.width(), 13);
277 EXPECT_EQ(oss.fill(),
'N');
282 std::vector<ros::Time> v1;
283 std::vector<ros::Time> v2;
286 for (uint32_t i = 0; i < v1.size(); i++)
290 t.
nsec = uint32_t(t.
nsec / 1000.0) * 1000;
291 boost::posix_time::ptime b = t.
toBoost();
303 EXPECT_NO_THROW(t1.
fromSec(4294967295.0));
304 EXPECT_NO_THROW(t2.
fromSec(4294967295.999));
305 EXPECT_NO_THROW(t3.
fromSec(0.0000001));
308 EXPECT_THROW(t1.
fromSec(4294967296.0), std::runtime_error);
309 EXPECT_THROW(t2.
fromSec(-0.0001), std::runtime_error);
310 EXPECT_THROW(t3.
fromSec(-4294967296.0), std::runtime_error);
317 Time t1(2147483648, 0);
318 Time t2(2147483647, 999999999);
319 Time t3(2147483647, 999999998);
320 Time t4(4294967295, 999999999);
321 Time t5(4294967295, 999999998);
329 EXPECT_NO_THROW(t1 - t2);
330 EXPECT_NO_THROW(t3 - t2);
331 EXPECT_NO_THROW(t4 - t5);
333 EXPECT_NO_THROW(t1 - d1);
334 EXPECT_NO_THROW(t5 - d1);
336 EXPECT_THROW(t4 - t6, std::runtime_error);
337 EXPECT_THROW(t4 - t3, std::runtime_error);
339 EXPECT_THROW(t1 - d2, std::runtime_error);
340 EXPECT_THROW(t2 - d2, std::runtime_error);
341 EXPECT_THROW(t4 - d3, std::runtime_error);
348 Time t1(2147483648, 0);
349 Time t2(2147483647, 999999999);
350 Time t4(4294967295, 999999999);
351 Time t5(4294967295, 999999998);
358 EXPECT_NO_THROW(t2 + d2);
359 EXPECT_NO_THROW(t1 + d1);
361 EXPECT_THROW(t4 + d4, std::runtime_error);
362 EXPECT_THROW(t4 + d1, std::runtime_error);
363 EXPECT_THROW(t5 + d3, std::runtime_error);
370 std::vector<ros::Duration> v1;
371 std::vector<ros::Duration> v2;
374 for (uint32_t i = 0; i < v1.size(); i++)
376 if (v1[i].sec * 1000000000LL + v1[i].nsec < v2[i].sec * 1000000000LL + v2[i].nsec)
378 EXPECT_LT(v1[i], v2[i]);
381 EXPECT_LE(v1[i], v2[i]);
382 EXPECT_NE(v1[i], v2[i]);
384 else if (v1[i].sec * 1000000000LL + v1[i].nsec > v2[i].sec * 1000000000LL + v2[i].nsec)
386 EXPECT_GT(v1[i], v2[i]);
389 EXPECT_GE(v1[i], v2[i]);
390 EXPECT_NE(v1[i], v2[i]);
394 EXPECT_EQ(v1[i], v2[i]);
395 EXPECT_LE(v1[i], v2[i]);
396 EXPECT_GE(v1[i], v2[i]);
404 std::vector<ros::Duration> v1;
405 std::vector<ros::Duration> v2;
408 for (uint32_t i = 0; i < v1.size(); i++)
410 EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
436 std::vector<ros::Duration> v1;
437 std::vector<ros::Duration> v2;
440 for (uint32_t i = 0; i < v1.size(); i++)
442 EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (v1[i] + v2[i]).toSec(),
epsilon);
444 EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (temp += v2[i]).toSec(),
epsilon);
452 std::vector<ros::Duration> v1;
453 std::vector<ros::Duration> v2;
456 for (uint32_t i = 0; i < v1.size(); i++)
458 EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (v1[i] - v2[i]).toSec(),
epsilon);
460 EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (temp -= v2[i]).toSec(),
epsilon);
462 EXPECT_NEAR(- v2[i].toSec(), (-v2[i]).toSec(),
epsilon);
477 std::vector<ros::Duration> v1;
478 std::vector<ros::Duration> v2;
481 for (uint32_t i = 0; i < v1.size(); i++)
483 EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (v1[i] * v2[i].toSec()).toSec(),
epsilon);
485 EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (temp *= v2[i].toSec()).toSec(),
epsilon);
496 EXPECT_EQ(t.
sec, 200L);
497 EXPECT_EQ(t.
nsec, 0L);
502 EXPECT_EQ(t.
sec, 0L);
503 EXPECT_EQ(t.
nsec, 100100L);
508 EXPECT_EQ(t.
sec, 12L);
509 EXPECT_EQ(t.
nsec, 3000L);
517 EXPECT_EQ(t.
sec, 0L);
518 EXPECT_EQ(t.
nsec, 0L);
523 EXPECT_EQ(t.
sec, 0L);
524 EXPECT_EQ(t.
nsec, 99900L);
529 EXPECT_EQ(t.
sec, 17L);
530 EXPECT_EQ(t.
nsec, 999997000L);
550 ASSERT_GT(end - start, d);
563 EXPECT_TRUE(r.
sleep());
569 EXPECT_FALSE(r.
sleep());
593 ASSERT_GT(end - start, d);
603 ASSERT_GT(finished, end);
607 int main(
int argc,
char **argv){
608 testing::InitGoogleTest(&argc, argv);
610 return RUN_ALL_TESTS();