test/time.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <vector>
31 
32 #include <gtest/gtest.h>
33 #include <ros/rate.h>
34 #include <ros/time.h>
35 #ifndef _WIN32
36 #include <sys/time.h>
37 #endif
38 
39 #include <boost/date_time/posix_time/ptime.hpp>
40 
41 using namespace ros;
42 
44 
45 double epsilon = 1e-9;
46 
47 void seed_rand()
48 {
49  //Seed random number generator with current microseond count
50 #ifndef _WIN32
51  timeval temp_time_struct;
52  gettimeofday(&temp_time_struct,NULL);
53  srand(temp_time_struct.tv_usec);
54 #else
55  srand(time(nullptr));
56 #endif
57 };
58 
59 void generate_rand_times(uint32_t range, uint64_t runs, std::vector<ros::Time>& values1, std::vector<ros::Time>& values2)
60 {
61  seed_rand();
62  values1.clear();
63  values2.clear();
64  values1.reserve(runs);
65  values2.reserve(runs);
66  for ( uint32_t i = 0; i < runs ; i++ )
67  {
68  values1.push_back(ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
69  values2.push_back(ros::Time( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
70  }
71 }
72 
73 void generate_rand_durations(uint32_t range, uint64_t runs, std::vector<ros::Duration>& values1, std::vector<ros::Duration>& values2)
74 {
75  seed_rand();
76  values1.clear();
77  values2.clear();
78  values1.reserve(runs * 4);
79  values2.reserve(runs * 4);
80  for ( uint32_t i = 0; i < runs ; i++ )
81  {
82  // positive durations
83  values1.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
84  values2.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
85  EXPECT_GE(values1.back(), ros::Duration(0,0));
86  EXPECT_GE(values2.back(), ros::Duration(0,0));
87 
88  // negative durations
89  values1.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
90  values2.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
91  EXPECT_LE(values1.back(), ros::Duration(0,0));
92  EXPECT_LE(values2.back(), ros::Duration(0,0));
93 
94  // positive and negative durations
95  values1.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
96  values2.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
97  EXPECT_GE(values1.back(), ros::Duration(0,0));
98  EXPECT_LE(values2.back(), ros::Duration(0,0));
99 
100  // negative and positive durations
101  values1.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
102  values2.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
103  EXPECT_LE(values1.back(), ros::Duration(0,0));
104  EXPECT_GE(values2.back(), ros::Duration(0,0));
105  }
106 }
107 
108 TEST(Time, size)
109 {
110  ASSERT_EQ(sizeof(Time), 8);
111  ASSERT_EQ(sizeof(Duration), 8);
112 }
113 
114 TEST(Time, Comparitors)
115 {
116  std::vector<ros::Time> v1;
117  std::vector<ros::Time> v2;
118  generate_rand_times(100, 1000, v1,v2);
119 
120  for (uint32_t i = 0; i < v1.size(); i++)
121  {
122  if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
123  {
124  EXPECT_LT(v1[i], v2[i]);
125  // printf("%f %d ", v1[i].toSec(), v1[i].sec * 1000000000ULL + v1[i].nsec);
126  //printf("vs %f %d\n", v2[i].toSec(), v2[i].sec * 1000000000ULL + v2[i].nsec);
127  EXPECT_LE(v1[i], v2[i]);
128  EXPECT_NE(v1[i], v2[i]);
129  }
130  else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
131  {
132  EXPECT_GT(v1[i], v2[i]);
133  EXPECT_GE(v1[i], v2[i]);
134  EXPECT_NE(v1[i], v2[i]);
135  }
136  else
137  {
138  EXPECT_EQ(v1[i], v2[i]);
139  EXPECT_LE(v1[i], v2[i]);
140  EXPECT_GE(v1[i], v2[i]);
141  }
142 
143  }
144 
145 }
146 
147 TEST(Time, ToFromDouble)
148 {
149  std::vector<ros::Time> v1;
150  std::vector<ros::Time> v2;
151  generate_rand_times(100, 1000, v1,v2);
152 
153  for (uint32_t i = 0; i < v1.size(); i++)
154  {
155  EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
156 
157  }
158 
159 }
160 
161 TEST(Time, RoundingError)
162 {
163  double someInt = 1031.0; // some integer
164  double t = std::nextafter(someInt, 0); // someint - epsilon
165  // t should be 1031.000000
166 
167  ros::Time exampleTime;
168  exampleTime.fromSec(t);
169 
170  // if rounded incorrectly, sec may be 1030
171  // and nsec may be 1e9.
172  EXPECT_EQ(exampleTime.sec, 1031);
173  EXPECT_EQ(exampleTime.nsec, 0);
174 }
175 
176 TEST(Time, OperatorPlus)
177 {
178  Time t(100, 0);
179  Duration d(100, 0);
180  Time r = t + d;
181  EXPECT_EQ(r.sec, 200UL);
182  EXPECT_EQ(r.nsec, 0UL);
183 
184  t = Time(0, 100000UL);
185  d = Duration(0, 100UL);
186  r = t + d;
187  EXPECT_EQ(r.sec, 0UL);
188  EXPECT_EQ(r.nsec, 100100UL);
189 
190  t = Time(0, 0);
191  d = Duration(10, 2000003000UL);
192  r = t + d;
193  EXPECT_EQ(r.sec, 12UL);
194  EXPECT_EQ(r.nsec, 3000UL);
195 }
196 
197 TEST(Time, OperatorMinus)
198 {
199  Time t(100, 0);
200  Duration d(100, 0);
201  Time r = t - d;
202  EXPECT_EQ(r.sec, 0UL);
203  EXPECT_EQ(r.nsec, 0UL);
204 
205  t = Time(0, 100000UL);
206  d = Duration(0, 100UL);
207  r = t - d;
208  EXPECT_EQ(r.sec, 0UL);
209  EXPECT_EQ(r.nsec, 99900UL);
210 
211  t = Time(30, 0);
212  d = Duration(10, 2000003000UL);
213  r = t - d;
214  EXPECT_EQ(r.sec, 17UL);
215  EXPECT_EQ(r.nsec, 999997000ULL);
216 }
217 
218 TEST(Time, OperatorPlusEquals)
219 {
220  Time t(100, 0);
221  Duration d(100, 0);
222  t += d;
223  EXPECT_EQ(t.sec, 200UL);
224  EXPECT_EQ(t.nsec, 0UL);
225 
226  t = Time(0, 100000UL);
227  d = Duration(0, 100UL);
228  t += d;
229  EXPECT_EQ(t.sec, 0UL);
230  EXPECT_EQ(t.nsec, 100100UL);
231 
232  t = Time(0, 0);
233  d = Duration(10, 2000003000UL);
234  t += d;
235  EXPECT_EQ(t.sec, 12UL);
236  EXPECT_EQ(t.nsec, 3000UL);
237 }
238 
239 TEST(Time, OperatorMinusEquals)
240 {
241  Time t(100, 0);
242  Duration d(100, 0);
243  t -= d;
244  EXPECT_EQ(t.sec, 0UL);
245  EXPECT_EQ(t.nsec, 0UL);
246 
247  t = Time(0, 100000UL);
248  d = Duration(0, 100UL);
249  t -= d;
250  EXPECT_EQ(t.sec, 0UL);
251  EXPECT_EQ(t.nsec, 99900UL);
252 
253  t = Time(30, 0);
254  d = Duration(10, 2000003000UL);
255  t -= d;
256  EXPECT_EQ(t.sec, 17UL);
257  EXPECT_EQ(t.nsec, 999997000ULL);
258 }
259 
260 TEST(Time, SecNSecConstructor)
261 {
262  Time t(100, 2000003000UL);
263  EXPECT_EQ(t.sec, 102UL);
264  EXPECT_EQ(t.nsec, 3000UL);
265 }
266 
267 TEST(Time, DontMungeStreamState)
268 {
269  std::ostringstream oss;
270  Time t(100, 2000003000UL);
271  oss << std::setfill('N');
272  oss << std::setw(13);
273  oss << t;
274 
275  EXPECT_EQ(oss.width(), 13);
276  EXPECT_EQ(oss.fill(), 'N');
277 }
278 
279 TEST(Time, ToFromBoost)
280 {
281  std::vector<ros::Time> v1;
282  std::vector<ros::Time> v2;
283  generate_rand_times(100, 1000, v1,v2);
284 
285  for (uint32_t i = 0; i < v1.size(); i++)
286  {
287  Time t = v1[i];
288  // dont assume that nanosecond are available
289  t.nsec = uint32_t(t.nsec / 1000.0) * 1000;
290  boost::posix_time::ptime b = t.toBoost();
291  Time tt = Time::fromBoost(b);
292  EXPECT_EQ(t, tt);
293  }
294 }
295 
296 TEST(Time, CastFromDoubleExceptions)
297 {
298  ros::Time::init();
299 
300  Time t1, t2, t3;
301  // Valid values to cast, must not throw exceptions
302  EXPECT_NO_THROW(t1.fromSec(4294967295.0));
303  EXPECT_NO_THROW(t2.fromSec(4294967295.999));
304  EXPECT_NO_THROW(t3.fromSec(0.0000001));
305 
306  // The next casts all incorrect.
307  EXPECT_THROW(t1.fromSec(4294967296.0), std::runtime_error);
308  EXPECT_THROW(t2.fromSec(-0.0001), std::runtime_error);
309  EXPECT_THROW(t3.fromSec(-4294967296.0), std::runtime_error);
310 }
311 
312 TEST(Time, OperatorMinusExceptions)
313 {
314  ros::Time::init();
315 
316  Time t1(2147483648, 0);
317  Time t2(2147483647, 999999999);
318  Time t3(2147483647, 999999998);
319  Time t4(4294967295, 999999999);
320  Time t5(4294967295, 999999998);
321  Time t6(0, 1);
322 
323  Duration d1(2147483647, 999999999);
324  Duration d2(-2147483648, 0);
325  Duration d3(-2147483648, 1);
326  Duration d4(0, 1);
327 
328  EXPECT_NO_THROW(t1 - t2);
329  EXPECT_NO_THROW(t3 - t2);
330  EXPECT_NO_THROW(t4 - t5);
331 
332  EXPECT_NO_THROW(t1 - d1);
333  EXPECT_NO_THROW(t5 - d1);
334 
335  EXPECT_THROW(t4 - t6, std::runtime_error);
336  EXPECT_THROW(t4 - t3, std::runtime_error);
337 
338  EXPECT_THROW(t1 - d2, std::runtime_error);
339  EXPECT_THROW(t2 - d2, std::runtime_error);
340  EXPECT_THROW(t4 - d3, std::runtime_error);
341 }
342 
343 TEST(Time, OperatorPlusExceptions)
344 {
345  ros::Time::init();
346 
347  Time t1(2147483648, 0);
348  Time t2(2147483647, 999999999);
349  Time t4(4294967295, 999999999);
350  Time t5(4294967295, 999999998);
351 
352  Duration d1(2147483647, 999999999);
353  Duration d2(-2147483648, 1);
354  Duration d3(0, 2);
355  Duration d4(0, 1);
356 
357  EXPECT_NO_THROW(t2 + d2);
358  EXPECT_NO_THROW(t1 + d1);
359 
360  EXPECT_THROW(t4 + d4, std::runtime_error);
361  EXPECT_THROW(t4 + d1, std::runtime_error);
362  EXPECT_THROW(t5 + d3, std::runtime_error);
363 }
364 
365 
366 /************************************* Duration Tests *****************/
367 
368 TEST(Duration, Comparitors)
369 {
370  std::vector<ros::Duration> v1;
371  std::vector<ros::Duration> v2;
372  generate_rand_durations(100, 1000, v1,v2);
373 
374  for (uint32_t i = 0; i < v1.size(); i++)
375  {
376  if (v1[i].sec * 1000000000LL + v1[i].nsec < v2[i].sec * 1000000000LL + v2[i].nsec)
377  {
378  EXPECT_LT(v1[i], v2[i]);
379 // printf("%f %lld ", v1[i].toSec(), v1[i].sec * 1000000000LL + v1[i].nsec);
380 // printf("vs %f %lld\n", v2[i].toSec(), v2[i].sec * 1000000000LL + v2[i].nsec);
381  EXPECT_LE(v1[i], v2[i]);
382  EXPECT_NE(v1[i], v2[i]);
383  }
384  else if (v1[i].sec * 1000000000LL + v1[i].nsec > v2[i].sec * 1000000000LL + v2[i].nsec)
385  {
386  EXPECT_GT(v1[i], v2[i]);
387 // printf("%f %lld ", v1[i].toSec(), v1[i].sec * 1000000000LL + v1[i].nsec);
388 // printf("vs %f %lld\n", v2[i].toSec(), v2[i].sec * 1000000000LL + v2[i].nsec);
389  EXPECT_GE(v1[i], v2[i]);
390  EXPECT_NE(v1[i], v2[i]);
391  }
392  else
393  {
394  EXPECT_EQ(v1[i], v2[i]);
395  EXPECT_LE(v1[i], v2[i]);
396  EXPECT_GE(v1[i], v2[i]);
397  }
398 
399  }
400 }
401 
402 TEST(Duration, ToFromSec)
403 {
404  std::vector<ros::Duration> v1;
405  std::vector<ros::Duration> v2;
406  generate_rand_durations(100, 1000, v1,v2);
407 
408  for (uint32_t i = 0; i < v1.size(); i++)
409  {
410  EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
411  EXPECT_GE(ros::Duration(v1[i].toSec()).nsec, 0);
412  }
413 
414  EXPECT_EQ(ros::Duration(-0.5), ros::Duration(-1LL, 500000000LL));
415  EXPECT_EQ(ros::Duration(-0.5), ros::Duration(0, -500000000LL));
416 }
417 
418 TEST(Duration, FromNSec)
419 {
420  ros::Duration t;
421  t.fromNSec(-500000000LL);
422  EXPECT_EQ(ros::Duration(-0.5), t);
423 
424  t.fromNSec(-1500000000LL);
425  EXPECT_EQ(ros::Duration(-1.5), t);
426 
427  t.fromNSec(500000000LL);
428  EXPECT_EQ(ros::Duration(0.5), t);
429 
430  t.fromNSec(1500000000LL);
431  EXPECT_EQ(ros::Duration(1.5), t);
432 }
433 
434 TEST(Duration, OperatorPlus)
435 {
436  std::vector<ros::Duration> v1;
437  std::vector<ros::Duration> v2;
438  generate_rand_durations(100, 1000, v1,v2);
439 
440  for (uint32_t i = 0; i < v1.size(); i++)
441  {
442  EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (v1[i] + v2[i]).toSec(), epsilon);
443  ros::Duration temp = v1[i];
444  EXPECT_NEAR(v1[i].toSec() + v2[i].toSec(), (temp += v2[i]).toSec(), epsilon);
445 
446  }
447 
448 }
449 
450 TEST(Duration, OperatorMinus)
451 {
452  std::vector<ros::Duration> v1;
453  std::vector<ros::Duration> v2;
454  generate_rand_durations(100, 1000, v1,v2);
455 
456  for (uint32_t i = 0; i < v1.size(); i++)
457  {
458  EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (v1[i] - v2[i]).toSec(), epsilon);
459  ros::Duration temp = v1[i];
460  EXPECT_NEAR(v1[i].toSec() - v2[i].toSec(), (temp -= v2[i]).toSec(), epsilon);
461 
462  EXPECT_NEAR(- v2[i].toSec(), (-v2[i]).toSec(), epsilon);
463 
464  }
465 
466  ros::Time t1(1.1);
467  ros::Time t2(1.3);
468  ros::Duration time_diff = t1 - t2; //=-0.2
469 
470  EXPECT_NEAR(time_diff.toSec(), -0.2, epsilon);
471  EXPECT_LE(time_diff, ros::Duration(-0.19));
472  EXPECT_GE(time_diff, ros::Duration(-0.21));
473 }
474 
475 TEST(Duration, OperatorTimes)
476 {
477  std::vector<ros::Duration> v1;
478  std::vector<ros::Duration> v2;
479  generate_rand_durations(100, 1000, v1,v2);
480 
481  for (uint32_t i = 0; i < v1.size(); i++)
482  {
483  EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (v1[i] * v2[i].toSec()).toSec(), epsilon);
484  ros::Duration temp = v1[i];
485  EXPECT_NEAR(v1[i].toSec() * v2[i].toSec(), (temp *= v2[i].toSec()).toSec(), epsilon);
486 
487  }
488 
489 }
490 
491 TEST(Duration, OperatorPlusEquals)
492 {
493  Duration t(100, 0);
494  Duration d(100, 0);
495  t += d;
496  EXPECT_EQ(t.sec, 200L);
497  EXPECT_EQ(t.nsec, 0L);
498 
499  t = Duration(0, 100000L);
500  d = Duration(0, 100L);
501  t += d;
502  EXPECT_EQ(t.sec, 0L);
503  EXPECT_EQ(t.nsec, 100100L);
504 
505  t = Duration(0, 0);
506  d = Duration(10, 2000003000L);
507  t += d;
508  EXPECT_EQ(t.sec, 12L);
509  EXPECT_EQ(t.nsec, 3000L);
510 }
511 
512 TEST(Duration, OperatorMinusEquals)
513 {
514  Duration t(100, 0);
515  Duration d(100, 0);
516  t -= d;
517  EXPECT_EQ(t.sec, 0L);
518  EXPECT_EQ(t.nsec, 0L);
519 
520  t = Duration(0, 100000L);
521  d = Duration(0, 100L);
522  t -= d;
523  EXPECT_EQ(t.sec, 0L);
524  EXPECT_EQ(t.nsec, 99900L);
525 
526  t = Duration(30, 0);
527  d = Duration(10, 2000003000L);
528  t -= d;
529  EXPECT_EQ(t.sec, 17L);
530  EXPECT_EQ(t.nsec, 999997000L);
531 }
532 
533 void alarmHandler(int sig)
534 {
535 
536 }
537 
538 TEST(Duration, sleepWithSignal)
539 {
540 #ifndef _WIN32
541  signal(SIGALRM, alarmHandler);
542  alarm(1);
543 #endif
544 
545  Time start = Time::now();
546  Duration d(2.0);
547  bool rc = d.sleep();
548  Time end = Time::now();
549 
550  ASSERT_GT(end - start, d);
551  ASSERT_TRUE(rc);
552 }
553 
554 TEST(Rate, constructFromDuration){
555  Duration d(4, 0);
556  Rate r(d);
557  EXPECT_EQ(r.expectedCycleTime(), d);
558 }
559 
560 TEST(Rate, sleep_return_value_true){
561  Rate r(Duration(0.2));
562  Duration(r.expectedCycleTime() * 0.5).sleep();
563  EXPECT_TRUE(r.sleep());
564 }
565 
566 TEST(Rate, sleep_return_value_false){
567  Rate r(Duration(0.2));
568  Duration(r.expectedCycleTime() * 2).sleep();
569  EXPECT_FALSE(r.sleep()); // requested rate cannot be achieved
570 }
571 
572 TEST(WallRate, constructFromDuration){
573  Duration d(4, 0);
574  WallRate r(d);
575  WallDuration wd(4, 0);
576  EXPECT_EQ(r.expectedCycleTime(), wd);
577 }
578 
580 // WallTime/WallDuration
582 
583 
585 // SteadyTime/WallDuration
587 
588 TEST(SteadyTime, sleep){
589  SteadyTime start = SteadyTime::now();
590  WallDuration d(2.0);
591  bool rc = d.sleep();
592  SteadyTime end = SteadyTime::now();
593 
594  ASSERT_GT(end - start, d);
595  ASSERT_TRUE(rc);
596 }
597 
598 TEST(SteadyTime, sleepUntil){
599  SteadyTime start = SteadyTime::now();
600  SteadyTime end = start + WallDuration(2.0);
601  bool rc = SteadyTime::sleepUntil(end);
602  SteadyTime finished = SteadyTime::now();
603 
604  ASSERT_GT(finished, end);
605  ASSERT_TRUE(rc);
606 }
607 
608 int main(int argc, char **argv){
609  testing::InitGoogleTest(&argc, argv);
610  ros::Time::init();
611  return RUN_ALL_TESTS();
612 }
double toSec() const
Definition: duration.h:93
double epsilon
Definition: test/time.cpp:45
void seed_rand()
Definition: test/time.cpp:47
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:170
uint32_t sec
Definition: time.h:133
bool sleep() const
sleep for the amount of time specified by this Duration. If a signal interrupts the sleep...
Definition: src/time.cpp:447
Class to help run loops at a desired frequency.
Definition: rate.h:51
Duration representation for use with the WallTime class.
Definition: duration.h:136
uint32_t nsec
Definition: time.h:133
int32_t nsec
Definition: duration.h:75
T & fromSec(double t)
Definition: impl/time.h:77
void alarmHandler(int sig)
Definition: test/time.cpp:533
Class to help run loops at a desired frequency. This version always uses wall-clock time...
Definition: rate.h:92
void generate_rand_durations(uint32_t range, uint64_t runs, std::vector< ros::Duration > &values1, std::vector< ros::Duration > &values2)
Definition: test/time.cpp:73
bool sleep() const
sleep for the amount of time specified by this Duration. If a signal interrupts the sleep...
Definition: src/time.cpp:531
static bool sleepUntil(const SteadyTime &end)
Sleep until a specific time has been reached.
Definition: src/time.cpp:436
static SteadyTime now()
Returns the current steady (monotonic) clock time.
Definition: src/time.cpp:509
TEST(Time, size)
Definition: test/time.cpp:108
Duration expectedCycleTime() const
Get the expected cycle time – one over the frequency passed in to the constructor.
Definition: rate.h:81
static void init()
Definition: src/time.cpp:312
Time representation. Always steady-clock time.
Definition: time.h:260
bool sleep()
Sleeps for any leftover time in a cycle. Calculated from the last time sleep, reset, or the constructor was called.
Definition: rate.cpp:56
Duration representation for use with the Time class.
Definition: duration.h:108
WallDuration expectedCycleTime() const
Get the expected cycle time – one over the frequency passed in to the constructor.
Definition: rate.h:122
T & fromNSec(int64_t t)
Definition: impl/duration.h:68
static Time now()
Retrieve the current time. If ROS clock time is in use, this returns the time according to the ROS cl...
Definition: src/time.cpp:284
static Time fromBoost(const boost::posix_time::ptime &t)
Definition: src/time.cpp:355
boost::posix_time::ptime toBoost() const
Definition: impl/time.h:177
void generate_rand_times(uint32_t range, uint64_t runs, std::vector< ros::Time > &values1, std::vector< ros::Time > &values2)
Definition: test/time.cpp:59
int main(int argc, char **argv)
Definition: test/time.cpp:608


rostime
Author(s): Josh Faust
autogenerated on Sat Apr 6 2019 02:52:21