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 
36 #if !defined(_WIN32)
37 #include <sys/time.h>
38 #endif
39 
40 #include <boost/date_time/posix_time/ptime.hpp>
41 
42 using namespace ros;
43 
45 
46 double epsilon = 1e-9;
47 
48 void seed_rand()
49 {
50  //Seed random number generator with current microseond count
51 #if !defined(_WIN32)
52  timeval temp_time_struct;
53  gettimeofday(&temp_time_struct,NULL);
54  srand(temp_time_struct.tv_usec);
55 #else
56  srand(time(nullptr));
57 #endif
58 };
59 
60 void generate_rand_times(uint32_t range, uint64_t runs, std::vector<ros::Time>& values1, std::vector<ros::Time>& values2)
61 {
62  seed_rand();
63  values1.clear();
64  values2.clear();
65  values1.reserve(runs);
66  values2.reserve(runs);
67  for ( uint32_t i = 0; i < runs ; i++ )
68  {
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)));
71  }
72 }
73 
74 void generate_rand_durations(uint32_t range, uint64_t runs, std::vector<ros::Duration>& values1, std::vector<ros::Duration>& values2)
75 {
76  seed_rand();
77  values1.clear();
78  values2.clear();
79  values1.reserve(runs * 4);
80  values2.reserve(runs * 4);
81  for ( uint32_t i = 0; i < runs ; i++ )
82  {
83  // positive durations
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)));
86  EXPECT_GE(values1.back(), ros::Duration(0,0));
87  EXPECT_GE(values2.back(), ros::Duration(0,0));
88 
89  // negative durations
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)));
92  EXPECT_LE(values1.back(), ros::Duration(0,0));
93  EXPECT_LE(values2.back(), ros::Duration(0,0));
94 
95  // positive and negative durations
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)));
98  EXPECT_GE(values1.back(), ros::Duration(0,0));
99  EXPECT_LE(values2.back(), ros::Duration(0,0));
100 
101  // negative and positive durations
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)));
104  EXPECT_LE(values1.back(), ros::Duration(0,0));
105  EXPECT_GE(values2.back(), ros::Duration(0,0));
106  }
107 }
108 
109 TEST(Time, size)
110 {
111  ASSERT_EQ(sizeof(Time), 8);
112  ASSERT_EQ(sizeof(Duration), 8);
113 }
114 
115 TEST(Time, Comparitors)
116 {
117  std::vector<ros::Time> v1;
118  std::vector<ros::Time> v2;
119  generate_rand_times(100, 1000, v1,v2);
120 
121  for (uint32_t i = 0; i < v1.size(); i++)
122  {
123  if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
124  {
125  EXPECT_LT(v1[i], v2[i]);
126  // printf("%f %d ", v1[i].toSec(), v1[i].sec * 1000000000ULL + v1[i].nsec);
127  //printf("vs %f %d\n", v2[i].toSec(), v2[i].sec * 1000000000ULL + v2[i].nsec);
128  EXPECT_LE(v1[i], v2[i]);
129  EXPECT_NE(v1[i], v2[i]);
130  }
131  else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
132  {
133  EXPECT_GT(v1[i], v2[i]);
134  EXPECT_GE(v1[i], v2[i]);
135  EXPECT_NE(v1[i], v2[i]);
136  }
137  else
138  {
139  EXPECT_EQ(v1[i], v2[i]);
140  EXPECT_LE(v1[i], v2[i]);
141  EXPECT_GE(v1[i], v2[i]);
142  }
143 
144  }
145 
146 }
147 
148 TEST(Time, ToFromDouble)
149 {
150  std::vector<ros::Time> v1;
151  std::vector<ros::Time> v2;
152  generate_rand_times(100, 1000, v1,v2);
153 
154  for (uint32_t i = 0; i < v1.size(); i++)
155  {
156  EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
157 
158  }
159 
160 }
161 
162 TEST(Time, RoundingError)
163 {
164  double someInt = 1031.0; // some integer
165  double t = std::nextafter(someInt, 0); // someint - epsilon
166  // t should be 1031.000000
167 
168  ros::Time exampleTime;
169  exampleTime.fromSec(t);
170 
171  // if rounded incorrectly, sec may be 1030
172  // and nsec may be 1e9.
173  EXPECT_EQ(exampleTime.sec, 1031);
174  EXPECT_EQ(exampleTime.nsec, 0);
175 }
176 
177 TEST(Time, OperatorPlus)
178 {
179  Time t(100, 0);
180  Duration d(100, 0);
181  Time r = t + d;
182  EXPECT_EQ(r.sec, 200UL);
183  EXPECT_EQ(r.nsec, 0UL);
184 
185  t = Time(0, 100000UL);
186  d = Duration(0, 100UL);
187  r = t + d;
188  EXPECT_EQ(r.sec, 0UL);
189  EXPECT_EQ(r.nsec, 100100UL);
190 
191  t = Time(0, 0);
192  d = Duration(10, 2000003000UL);
193  r = t + d;
194  EXPECT_EQ(r.sec, 12UL);
195  EXPECT_EQ(r.nsec, 3000UL);
196 }
197 
198 TEST(Time, OperatorMinus)
199 {
200  Time t(100, 0);
201  Duration d(100, 0);
202  Time r = t - d;
203  EXPECT_EQ(r.sec, 0UL);
204  EXPECT_EQ(r.nsec, 0UL);
205 
206  t = Time(0, 100000UL);
207  d = Duration(0, 100UL);
208  r = t - d;
209  EXPECT_EQ(r.sec, 0UL);
210  EXPECT_EQ(r.nsec, 99900UL);
211 
212  t = Time(30, 0);
213  d = Duration(10, 2000003000UL);
214  r = t - d;
215  EXPECT_EQ(r.sec, 17UL);
216  EXPECT_EQ(r.nsec, 999997000ULL);
217 }
218 
219 TEST(Time, OperatorPlusEquals)
220 {
221  Time t(100, 0);
222  Duration d(100, 0);
223  t += d;
224  EXPECT_EQ(t.sec, 200UL);
225  EXPECT_EQ(t.nsec, 0UL);
226 
227  t = Time(0, 100000UL);
228  d = Duration(0, 100UL);
229  t += d;
230  EXPECT_EQ(t.sec, 0UL);
231  EXPECT_EQ(t.nsec, 100100UL);
232 
233  t = Time(0, 0);
234  d = Duration(10, 2000003000UL);
235  t += d;
236  EXPECT_EQ(t.sec, 12UL);
237  EXPECT_EQ(t.nsec, 3000UL);
238 }
239 
240 TEST(Time, OperatorMinusEquals)
241 {
242  Time t(100, 0);
243  Duration d(100, 0);
244  t -= d;
245  EXPECT_EQ(t.sec, 0UL);
246  EXPECT_EQ(t.nsec, 0UL);
247 
248  t = Time(0, 100000UL);
249  d = Duration(0, 100UL);
250  t -= d;
251  EXPECT_EQ(t.sec, 0UL);
252  EXPECT_EQ(t.nsec, 99900UL);
253 
254  t = Time(30, 0);
255  d = Duration(10, 2000003000UL);
256  t -= d;
257  EXPECT_EQ(t.sec, 17UL);
258  EXPECT_EQ(t.nsec, 999997000ULL);
259 }
260 
261 TEST(Time, SecNSecConstructor)
262 {
263  Time t(100, 2000003000UL);
264  EXPECT_EQ(t.sec, 102UL);
265  EXPECT_EQ(t.nsec, 3000UL);
266 }
267 
268 TEST(Time, DontMungeStreamState)
269 {
270  std::ostringstream oss;
271  Time t(100, 2000003000UL);
272  oss << std::setfill('N');
273  oss << std::setw(13);
274  oss << t;
275 
276  EXPECT_EQ(oss.width(), 13);
277  EXPECT_EQ(oss.fill(), 'N');
278 }
279 
280 TEST(Time, ToFromBoost)
281 {
282  std::vector<ros::Time> v1;
283  std::vector<ros::Time> v2;
284  generate_rand_times(100, 1000, v1,v2);
285 
286  for (uint32_t i = 0; i < v1.size(); i++)
287  {
288  Time t = v1[i];
289  // dont assume that nanosecond are available
290  t.nsec = uint32_t(t.nsec / 1000.0) * 1000;
291  boost::posix_time::ptime b = t.toBoost();
292  Time tt = Time::fromBoost(b);
293  EXPECT_EQ(t, tt);
294  }
295 }
296 
297 TEST(Time, CastFromDoubleExceptions)
298 {
299  ros::Time::init();
300 
301  Time t1, t2, t3;
302  // Valid values to cast, must not throw exceptions
303  EXPECT_NO_THROW(t1.fromSec(4294967295.0));
304  EXPECT_NO_THROW(t2.fromSec(4294967295.999));
305  EXPECT_NO_THROW(t3.fromSec(0.0000001));
306 
307  // The next casts all incorrect.
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);
311 }
312 
313 TEST(Time, OperatorMinusExceptions)
314 {
315  ros::Time::init();
316 
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);
322  Time t6(0, 1);
323 
324  Duration d1(2147483647, 999999999);
325  Duration d2(-2147483648, 0);
326  Duration d3(-2147483648, 1);
327  Duration d4(0, 1);
328 
329  EXPECT_NO_THROW(t1 - t2);
330  EXPECT_NO_THROW(t3 - t2);
331  EXPECT_NO_THROW(t4 - t5);
332 
333  EXPECT_NO_THROW(t1 - d1);
334  EXPECT_NO_THROW(t5 - d1);
335 
336  EXPECT_THROW(t4 - t6, std::runtime_error);
337  EXPECT_THROW(t4 - t3, std::runtime_error);
338 
339  EXPECT_THROW(t1 - d2, std::runtime_error);
340  EXPECT_THROW(t2 - d2, std::runtime_error);
341  EXPECT_THROW(t4 - d3, std::runtime_error);
342 }
343 
344 TEST(Time, OperatorPlusExceptions)
345 {
346  ros::Time::init();
347 
348  Time t1(2147483648, 0);
349  Time t2(2147483647, 999999999);
350  Time t4(4294967295, 999999999);
351  Time t5(4294967295, 999999998);
352 
353  Duration d1(2147483647, 999999999);
354  Duration d2(-2147483648, 1);
355  Duration d3(0, 2);
356  Duration d4(0, 1);
357 
358  EXPECT_NO_THROW(t2 + d2);
359  EXPECT_NO_THROW(t1 + d1);
360 
361  EXPECT_THROW(t4 + d4, std::runtime_error);
362  EXPECT_THROW(t4 + d1, std::runtime_error);
363  EXPECT_THROW(t5 + d3, std::runtime_error);
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 #if !defined(_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 
584 // SteadyTime/WallDuration
586 
587 TEST(SteadyTime, sleep){
588  SteadyTime start = SteadyTime::now();
589  WallDuration d(2.0);
590  bool rc = d.sleep();
591  SteadyTime end = SteadyTime::now();
592 
593  ASSERT_GT(end - start, d);
594  ASSERT_TRUE(rc);
595 }
596 
597 TEST(SteadyTime, sleepUntil){
598  SteadyTime start = SteadyTime::now();
599  SteadyTime end = start + WallDuration(2.0);
600  bool rc = SteadyTime::sleepUntil(end);
601  SteadyTime finished = SteadyTime::now();
602 
603  ASSERT_GT(finished, end);
604  ASSERT_TRUE(rc);
605 }
606 
607 int main(int argc, char **argv){
608  testing::InitGoogleTest(&argc, argv);
609  ros::Time::init();
610  return RUN_ALL_TESTS();
611 }
double epsilon
Definition: test/time.cpp:46
void seed_rand()
Definition: test/time.cpp:48
Time representation. May either represent wall clock time or ROS clock time.
Definition: time.h:170
uint32_t sec
Definition: time.h:133
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
WallDuration expectedCycleTime() const
Get the expected cycle time – one over the frequency passed in to the constructor.
Definition: rate.h:122
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:74
static bool sleepUntil(const SteadyTime &end)
Sleep until a specific time has been reached.
Definition: src/time.cpp:373
static SteadyTime now()
Returns the current steady (monotonic) clock time.
Definition: src/time.cpp:446
TEST(Time, size)
Definition: test/time.cpp:109
static void init()
Definition: src/time.cpp:249
bool sleep() const
sleep for the amount of time specified by this Duration. If a signal interrupts the sleep...
Definition: src/time.cpp:468
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:54
double toSec() const
Definition: duration.h:93
Duration representation for use with the Time class.
Definition: duration.h:108
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:221
static Time fromBoost(const boost::posix_time::ptime &t)
Definition: src/time.cpp:292
bool sleep() const
sleep for the amount of time specified by this Duration. If a signal interrupts the sleep...
Definition: src/time.cpp:384
void generate_rand_times(uint32_t range, uint64_t runs, std::vector< ros::Time > &values1, std::vector< ros::Time > &values2)
Definition: test/time.cpp:60
int main(int argc, char **argv)
Definition: test/time.cpp:607
Duration expectedCycleTime() const
Get the expected cycle time – one over the frequency passed in to the constructor.
Definition: rate.h:81
boost::posix_time::ptime toBoost() const
Definition: impl/time.h:177


rostime
Author(s): Josh Faust
autogenerated on Mon Feb 28 2022 23:31:37