timer_callbacks.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 /* Author: Josh Faust */
31 
32 /*
33  * Test timer callbacks
34  */
35 
36 #include <string>
37 #include <sstream>
38 #include <fstream>
39 
40 #include <gtest/gtest.h>
41 
42 #include <time.h>
43 #include <stdlib.h>
44 
45 #include "ros/ros.h"
46 #include "ros/callback_queue.h"
47 #include <test_roscpp/TestArray.h>
48 #include <test_roscpp/TestStringString.h>
49 
50 #include <boost/scoped_ptr.hpp>
51 
52 using namespace ros;
53 using namespace test_roscpp;
54 
55 std::string g_node_name = "test_timer_callbacks";
56 
57 
58 /************************* SteadyTimer tests **********************/
59 
61 {
62  public:
63  SteadyTimerHelper(float period, bool oneshot = false)
64  : expected_period_(period)
65  , failed_(false)
66  , total_calls_(0)
67  , testing_period_(false)
68  , calls_before_testing_period_(0)
69  {
70  NodeHandle n;
71  timer_ = n.createSteadyTimer(expected_period_, &SteadyTimerHelper::callback, this, oneshot);
72  }
73 
74  void callback(const SteadyTimerEvent& e)
75  {
76  bool first = last_call_.isZero();
77  last_call_ = e.current_real;
78 
79  if (!first)
80  {
81  double time_error = e.current_real.toSec() - e.current_expected.toSec();
82  // Strict check if called early, loose check if called late.
83  // Yes, this is very loose, but must pass in high-load, containerized/virtualized, contentious environments.
84  if (time_error > 5.0 || time_error < -0.01)
85  {
86  ROS_ERROR("Call came at wrong time (expected: %f, actual %f)", e.current_expected.toSec(), e.current_real.toSec());
87  failed_ = true;
88  }
89  }
90 
91  if(testing_period_)
92  {
93 
94  // Inside callback, less than current period, reset=false
95  if(total_calls_ == calls_before_testing_period_)
96  {
97  WallDuration p(0.5);
98  pretendWork(0.15);
99  setPeriod(p);
100  }
101 
102  // Inside callback, greater than current period, reset=false
103  else if(total_calls_ == (calls_before_testing_period_+1))
104  {
105  WallDuration p(0.25);
106  pretendWork(0.15);
107  setPeriod(p);
108  }
109 
110  // Inside callback, less than current period, reset=true
111  else if(total_calls_ == (calls_before_testing_period_+2))
112  {
113  WallDuration p(0.5);
114  pretendWork(0.15);
115  setPeriod(p, true);
116  }
117 
118  // Inside callback, greater than current period, reset=true
119  else if(total_calls_ == (calls_before_testing_period_+3))
120  {
121  WallDuration p(0.25);
122  pretendWork(0.15);
123  setPeriod(p, true);
124  }
125  }
126 
127  ++total_calls_;
128  }
129 
130  void setPeriod(const WallDuration p, bool reset=false)
131  {
132  timer_.setPeriod(p, reset);
133  expected_period_ = p;
134  }
135 
136 
137  void pretendWork(const float t)
138  {
139  ros::Rate r(1. / t);
140  r.sleep();
141  }
142 
145 
146  bool failed_;
147 
149  int32_t total_calls_;
150 
153 };
154 
155 TEST(RoscppTimerCallbacks, singleSteadyTimeCallback)
156 {
157  NodeHandle n;
158  SteadyTimerHelper helper1(0.01);
159 
160  WallDuration d(0.001f);
161  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
162  {
163  spinOnce();
164  d.sleep();
165  }
166 
167  if (helper1.failed_)
168  {
169  FAIL();
170  }
171 
172  if (helper1.total_calls_ < 99)
173  {
174  ROS_ERROR("Total calls: %d (expected at least 100)", helper1.total_calls_);
175  FAIL();
176  }
177 }
178 
179 TEST(RoscppTimerCallbacks, multipleSteadyTimeCallbacks)
180 {
181  NodeHandle n;
182  const int count = 100;
183  typedef boost::scoped_ptr<SteadyTimerHelper> HelperPtr;
184  HelperPtr helpers[count];
185  for (int i = 0; i < count; ++i)
186  {
187  helpers[i].reset(new SteadyTimerHelper((float)(i + 1) * 0.1f));
188  }
189 
190  WallDuration d(0.01f);
191  const int spin_count = 1000;
192  for (int32_t i = 0; i < spin_count && n.ok(); ++i)
193  {
194  spinOnce();
195  d.sleep();
196  }
197 
198  for (int i = 0; i < count; ++i)
199  {
200  if (helpers[i]->failed_)
201  {
202  ROS_ERROR("Helper %d failed", i);
203  FAIL();
204  }
205 
206  int32_t expected_count = (spin_count * d.toSec()) / helpers[i]->expected_period_.toSec();
207  if (helpers[i]->total_calls_ < (expected_count - 1))
208  {
209  ROS_ERROR("Helper %d total calls: %d (at least %d expected)", i, helpers[i]->total_calls_, expected_count);
210  FAIL();
211  }
212  }
213 }
214 
215 TEST(RoscppTimerCallbacks, steadySetPeriod)
216 {
217  NodeHandle n;
218  WallDuration period(0.5);
219  SteadyTimerHelper helper(period.toSec());
220  Rate r(100);
221 
222  // Let the callback occur once before getting started
223  while(helper.total_calls_ < 1)
224  {
225  spinOnce();
226  r.sleep();
227  }
228 
229  helper.pretendWork(0.1);
230 
231  // outside callback, new period < old period, reset = false
232  Duration wait(0.5);
233  WallDuration p(0.25);
234  helper.setPeriod(p);
235  while(helper.total_calls_ < 2)
236  {
237  spinOnce();
238  r.sleep();
239  }
240 
241  helper.pretendWork(0.1);
242 
243  // outside callback, new period > old period, reset = false
244  WallDuration p2(0.5);
245  helper.setPeriod(p);
246  while(helper.total_calls_ < 3)
247  {
248  spinOnce();
249  r.sleep();
250  }
251 
252  helper.pretendWork(0.1);
253 
254  // outside callback, new period < old period, reset = true
255  WallDuration p3(0.25);
256  helper.setPeriod(p, true);
257  while(helper.total_calls_ < 4)
258  {
259  spinOnce();
260  r.sleep();
261  }
262 
263  helper.pretendWork(0.1);
264 
265  // outside callback, new period > old period, reset = true
266  WallDuration p4(0.5);
267  helper.setPeriod(p, true);
268  while(helper.total_calls_ < 5)
269  {
270  spinOnce();
271  r.sleep();
272  }
273 
274  // Test calling setPeriod inside callback
275  helper.calls_before_testing_period_ = helper.total_calls_;
276  int total = helper.total_calls_ + 5;
277  helper.testing_period_ = true;
278  while(helper.total_calls_ < total)
279  {
280  spinOnce();
281  r.sleep();
282  }
283  helper.testing_period_ = false;
284 
285 
286  if(helper.failed_)
287  {
288  ROS_ERROR("Helper failed in setPeriod");
289  FAIL();
290  }
291 }
292 
293 TEST(RoscppTimerCallbacks, stopSteadyTimer)
294 {
295  NodeHandle n;
296  SteadyTimerHelper helper(0.001);
297 
298  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
299  {
300  WallDuration(0.001).sleep();
301  spinOnce();
302  }
303 
304  ASSERT_GT(helper.total_calls_, 0);
305  int32_t last_count = helper.total_calls_;
306  helper.timer_.stop();
307 
308  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
309  {
310  WallDuration(0.001).sleep();
311  spinOnce();
312  }
313 
314  ASSERT_EQ(last_count, helper.total_calls_);
315 }
316 
317 int32_t g_steady_count = 0;
319 {
320  ++g_steady_count;
321 }
322 
323 TEST(RoscppTimerCallbacks, steadyStopThenSpin)
324 {
325  g_steady_count = 0;
326  NodeHandle n;
328 
329  WallDuration(0.1).sleep();
330  timer.stop();
331 
332  spinOnce();
333 
334  ASSERT_EQ(g_steady_count, 0);
335 }
336 
337 TEST(RoscppTimerCallbacks, oneShotSteadyTimer)
338 {
339  NodeHandle n;
340  SteadyTimerHelper helper(0.001, true);
341 
342  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
343  {
344  WallDuration(0.001).sleep();
345  spinOnce();
346  }
347 
348  ASSERT_EQ(helper.total_calls_, 1);
349 }
350 
351 /************************* WallTimer tests **********************/
352 
354 {
355 public:
356  WallTimerHelper(float period, bool oneshot = false)
357  : expected_period_(period)
358  , failed_(false)
359  , total_calls_(0)
360  , testing_period_(false)
361  , calls_before_testing_period_(0)
362  {
363  NodeHandle n;
364  timer_ = n.createWallTimer(expected_period_, &WallTimerHelper::callback, this, oneshot);
365  }
366 
367  void callback(const WallTimerEvent& e)
368  {
369  bool first = last_call_.isZero();
370  last_call_ = e.current_real;
371 
372  if (!first)
373  {
374  double time_error = e.current_real.toSec() - e.current_expected.toSec();
375  // Strict check if called early, loose check if called late.
376  // Yes, this is very loose, but must pass in high-load, containerized/virtualized, contentious environments.
377  if (time_error > 5.0 || time_error < -0.01)
378  {
379  ROS_ERROR("Call came at wrong time (expected: %f, actual %f)", e.current_expected.toSec(), e.current_real.toSec());
380  failed_ = true;
381  }
382  }
383 
384  if(testing_period_)
385  {
386 
387  // Inside callback, less than current period, reset=false
388  if(total_calls_ == calls_before_testing_period_)
389  {
390  WallDuration p(0.5);
391  pretendWork(0.15);
392  setPeriod(p);
393  }
394 
395  // Inside callback, greater than current period, reset=false
396  else if(total_calls_ == (calls_before_testing_period_+1))
397  {
398  WallDuration p(0.25);
399  pretendWork(0.15);
400  setPeriod(p);
401  }
402 
403  // Inside callback, less than current period, reset=true
404  else if(total_calls_ == (calls_before_testing_period_+2))
405  {
406  WallDuration p(0.5);
407  pretendWork(0.15);
408  setPeriod(p, true);
409  }
410 
411  // Inside callback, greater than current period, reset=true
412  else if(total_calls_ == (calls_before_testing_period_+3))
413  {
414  WallDuration p(0.25);
415  pretendWork(0.15);
416  setPeriod(p, true);
417  }
418  }
419 
420  ++total_calls_;
421  }
422 
423  void setPeriod(const WallDuration p, bool reset=false)
424  {
425  timer_.setPeriod(p, reset);
426  expected_period_ = p;
427  }
428 
429 
430  void pretendWork(const float t)
431  {
432  ros::Rate r(1. / t);
433  r.sleep();
434  }
435 
438 
439  bool failed_;
440 
442  int32_t total_calls_;
443 
446 };
447 
448 TEST(RoscppTimerCallbacks, singleWallTimeCallback)
449 {
450  NodeHandle n;
451  WallTimerHelper helper1(0.01);
452 
453  WallDuration d(0.001f);
454  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
455  {
456  spinOnce();
457  d.sleep();
458  }
459 
460  if (helper1.failed_)
461  {
462  FAIL();
463  }
464 
465  if (helper1.total_calls_ < 99)
466  {
467  ROS_ERROR("Total calls: %d (expected at least 100)", helper1.total_calls_);
468  FAIL();
469  }
470 }
471 
472 TEST(RoscppTimerCallbacks, multipleWallTimeCallbacks)
473 {
474  NodeHandle n;
475  const int count = 100;
476  typedef boost::scoped_ptr<WallTimerHelper> HelperPtr;
477  HelperPtr helpers[count];
478  for (int i = 0; i < count; ++i)
479  {
480  helpers[i].reset(new WallTimerHelper((float)(i + 1) * 0.1f));
481  }
482 
483  WallDuration d(0.01f);
484  const int spin_count = 1000;
485  for (int32_t i = 0; i < spin_count && n.ok(); ++i)
486  {
487  spinOnce();
488  d.sleep();
489  }
490 
491  for (int i = 0; i < count; ++i)
492  {
493  if (helpers[i]->failed_)
494  {
495  ROS_ERROR("Helper %d failed", i);
496  FAIL();
497  }
498 
499  int32_t expected_count = (spin_count * d.toSec()) / helpers[i]->expected_period_.toSec();
500  if (helpers[i]->total_calls_ < (expected_count - 1))
501  {
502  ROS_ERROR("Helper %d total calls: %d (at least %d expected)", i, helpers[i]->total_calls_, expected_count);
503  FAIL();
504  }
505  }
506 }
507 
508 TEST(RoscppTimerCallbacks, setPeriod)
509 {
510  NodeHandle n;
511  WallDuration period(0.5);
512  WallTimerHelper helper(period.toSec());
513  Rate r(100);
514 
515  // Let the callback occur once before getting started
516  while(helper.total_calls_ < 1)
517  {
518  spinOnce();
519  r.sleep();
520  }
521 
522  helper.pretendWork(0.1);
523 
524  // outside callback, new period < old period, reset = false
525  Time start = Time::now();
526  Duration wait(0.5);
527  WallDuration p(0.25);
528  helper.setPeriod(p);
529  while(helper.total_calls_ < 2)
530  {
531  spinOnce();
532  r.sleep();
533  }
534 
535  helper.pretendWork(0.1);
536 
537  // outside callback, new period > old period, reset = false
538  WallDuration p2(0.5);
539  start = Time::now();
540  helper.setPeriod(p);
541  while(helper.total_calls_ < 3)
542  {
543  spinOnce();
544  r.sleep();
545  }
546 
547  helper.pretendWork(0.1);
548 
549  // outside callback, new period < old period, reset = true
550  WallDuration p3(0.25);
551  start = Time::now();
552  helper.setPeriod(p, true);
553  while(helper.total_calls_ < 4)
554  {
555  spinOnce();
556  r.sleep();
557  }
558 
559  helper.pretendWork(0.1);
560 
561  // outside callback, new period > old period, reset = true
562  WallDuration p4(0.5);
563  start = Time::now();
564  helper.setPeriod(p, true);
565  while(helper.total_calls_ < 5)
566  {
567  spinOnce();
568  r.sleep();
569  }
570 
571  // Test calling setPeriod inside callback
572  helper.calls_before_testing_period_ = helper.total_calls_;
573  int total = helper.total_calls_ + 5;
574  helper.testing_period_ = true;
575  while(helper.total_calls_ < total)
576  {
577  spinOnce();
578  r.sleep();
579  }
580  helper.testing_period_ = false;
581 
582 
583  if(helper.failed_)
584  {
585  ROS_ERROR("Helper failed in setPeriod");
586  FAIL();
587  }
588 }
589 
590 TEST(RoscppTimerCallbacks, stopWallTimer)
591 {
592  NodeHandle n;
593  WallTimerHelper helper(0.001);
594 
595  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
596  {
597  WallDuration(0.001).sleep();
598  spinOnce();
599  }
600 
601  ASSERT_GT(helper.total_calls_, 0);
602  int32_t last_count = helper.total_calls_;
603  helper.timer_.stop();
604 
605  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
606  {
607  WallDuration(0.001).sleep();
608  spinOnce();
609  }
610 
611  ASSERT_EQ(last_count, helper.total_calls_);
612 }
613 
614 int32_t g_count = 0;
616 {
617  ++g_count;
618 }
619 
620 TEST(RoscppTimerCallbacks, stopThenSpin)
621 {
622  g_count = 0;
623  NodeHandle n;
625 
626  WallDuration(0.1).sleep();
627  timer.stop();
628 
629  spinOnce();
630 
631  ASSERT_EQ(g_count, 0);
632 }
633 
634 TEST(RoscppTimerCallbacks, oneShotWallTimer)
635 {
636  NodeHandle n;
637  WallTimerHelper helper(0.001, true);
638 
639  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
640  {
641  WallDuration(0.001).sleep();
642  spinOnce();
643  }
644 
645  ASSERT_EQ(helper.total_calls_, 1);
646 }
647 
649 {
650 public:
651  TimerHelper(Duration period, bool oneshot = false)
652  : failed_(false)
653  , expected_period_(period)
654  , total_calls_(0)
655  {
656  NodeHandle n;
657  timer_ = n.createTimer(expected_period_, &TimerHelper::callback, this, oneshot);
658  }
659 
660  TimerHelper(Rate r, bool oneshot = false)
661  : failed_(false)
662  , expected_period_(r.expectedCycleTime())
663  , total_calls_(0)
664  {
665  NodeHandle n;
666  timer_ = n.createTimer(r, &TimerHelper::callback, this, oneshot);
667  }
668 
669  void callback(const TimerEvent&)
670  {
671  ++total_calls_;
672  }
673 
674  bool failed_;
675 
677 
679  int32_t total_calls_;
680 };
681 
682 TEST(RoscppTimerCallbacks, singleROSTimeCallback)
683 {
684  NodeHandle n;
685 
686  Time now(1, 0);
687  Time::setNow(now);
688 
689  TimerHelper helper(Duration(0, 10000000));
690 
691  Duration d(0, 1000000);
692  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
693  {
694  now += d;
695  Time::setNow(now);
696 
697  while (helper.timer_.hasPending())
698  {
699  WallDuration(0.001).sleep();
700  spinOnce();
701  }
702  }
703 
704  if (helper.failed_)
705  {
706  FAIL();
707  }
708 
709  if (helper.total_calls_ != 100)
710  {
711  ROS_ERROR("Total calls: %d (expected 100)", helper.total_calls_);
712  FAIL();
713  }
714 }
715 
716 TEST(RoscppTimerCallbacks, singleROSTimeCallbackFromRate)
717 {
718  NodeHandle n;
719 
720  Time now(1, 0);
721  Time::setNow(now);
722 
723  TimerHelper helper(Rate(100));
724 
725  Duration d(0, 1000000);
726  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
727  {
728  now += d;
729  Time::setNow(now);
730 
731  while (helper.timer_.hasPending())
732  {
733  WallDuration(0.00025).sleep();
734  spinOnce();
735  }
736  }
737 
738  if (helper.failed_)
739  {
740  FAIL();
741  }
742 
743  if (helper.total_calls_ != 100)
744  {
745  ROS_ERROR("Total calls: %d (expected 100)", helper.total_calls_);
746  FAIL();
747  }
748 }
749 
750 TEST(RoscppTimerCallbacks, oneshotROSTimer)
751 {
752  NodeHandle n;
753 
754  Time now(1, 0);
755  Time::setNow(now);
756 
757  TimerHelper helper(Duration(0, 10000000), true);
758 
759  Duration d(0, 1000000);
760  for (int32_t i = 0; i < 1000 && n.ok(); ++i)
761  {
762  now += d;
763  Time::setNow(now);
764 
765  while (helper.timer_.hasPending())
766  {
767  WallDuration(0.001).sleep();
768  spinOnce();
769  }
770  }
771 
772  if (helper.failed_)
773  {
774  FAIL();
775  }
776 
777  ASSERT_EQ(helper.total_calls_, 1);
778 }
779 
780 TEST(RoscppTimerCallbacks, singleROSTimeCallbackLargeTimestep)
781 {
782  NodeHandle n;
783 
784  Time now(1, 0);
785  Time::setNow(now);
786 
787  TimerHelper helper(Duration(0, 10000000));
788 
789  Duration d(0, 100000000);
790  for (int32_t i = 0; i < 100 && n.ok(); ++i)
791  {
792  now += d;
793  Time::setNow(now);
794 
795  while (helper.timer_.hasPending())
796  {
797  WallDuration(0.001).sleep();
798  spinOnce();
799  }
800  }
801 
802  if (helper.failed_)
803  {
804  FAIL();
805  }
806 
807  if (helper.total_calls_ != 200)
808  {
809  ROS_ERROR("Total calls: %d (expected 200)", helper.total_calls_);
810  FAIL();
811  }
812 }
813 
814 TEST(RoscppTimerCallbacks, multipleROSTimeCallbacks)
815 {
816  NodeHandle n;
817 
818  Time now(1, 0);
819  Time::setNow(now);
820 
821  const int count = 100;
822  typedef boost::scoped_ptr<TimerHelper> HelperPtr;
823  HelperPtr helpers[count];
824  for (int i = 0; i < count; ++i)
825  {
826  helpers[i].reset(new TimerHelper(Duration((float)(i + 1) * 0.01f)));
827  }
828 
829  Duration d(0.001f);
830  const int spin_count = 1000;
831  for (int32_t i = 0; i < spin_count && n.ok(); ++i)
832  {
833  now += d;
834  Time::setNow(now);
835 
836  bool pending = false;
837 
838  do
839  {
840  pending = false;
841  for (int i = 0; i < count; ++i)
842  {
843  pending |= helpers[i]->timer_.hasPending();
844  }
845 
846  WallDuration(0.001).sleep();
847  spinOnce();
848  } while (pending);
849  }
850 
851  for (int i = 0; i < count; ++i)
852  {
853  if (helpers[i]->failed_)
854  {
855  ROS_ERROR("Helper %d failed", i);
856  FAIL();
857  }
858 
859  int32_t expected_count = (spin_count * d.toSec()) / helpers[i]->expected_period_.toSec();
860  if (helpers[i]->total_calls_ < (expected_count - 1) || helpers[i]->total_calls_ > (expected_count + 1))
861  {
862  ROS_ERROR("Helper %d total calls: %d (%d expected)", i, helpers[i]->total_calls_, expected_count);
863  FAIL();
864  }
865  }
866 }
867 
868 class Tracked
869 {
870 public:
872  {
873  g_count = 0;
874  }
875 
876  void callback(const TimerEvent&)
877  {
878  ++g_count;
879  }
880 };
881 
882 TEST(RoscppTimerCallbacks, trackedObject)
883 {
884  NodeHandle n;
885  Time now(1, 0);
886  Time::setNow(now);
887 
888  boost::shared_ptr<Tracked> tracked(boost::make_shared<Tracked>());
889  Timer timer = n.createTimer(Duration(0.001), &Tracked::callback, tracked);
890 
891  now += Duration(0.1);
892  Time::setNow(now);
893 
894  while (timer.hasPending())
895  {
896  WallDuration(0.001).sleep();
897  spinOnce();
898  }
899 
900  ASSERT_GT(g_count, 0);
901  int32_t last_count = g_count;
902  tracked.reset();
903 
904  now += Duration(0.1);
905  Time::setNow(now);
906 
907  while (timer.hasPending())
908  {
909  WallDuration(0.001).sleep();
910  spinOnce();
911  }
912 
913  ASSERT_EQ(last_count, g_count);
914 }
915 
916 TEST(RoscppTimerCallbacks, stopROSTimer)
917 {
918  NodeHandle n;
919  Time now(1, 0);
920  Time::setNow(now);
921 
922  TimerHelper helper(Duration(0.001));
923 
924  now += Duration(0.1);
925  Time::setNow(now);
926 
927  while (helper.timer_.hasPending())
928  {
929  WallDuration(0.001).sleep();
930  spinOnce();
931  }
932 
933  ASSERT_GT(helper.total_calls_, 0);
934  int32_t last_count = helper.total_calls_;
935  helper.timer_.stop();
936 
937  now += Duration(0.1);
938  Time::setNow(now);
939 
940  while (helper.timer_.hasPending())
941  {
942  WallDuration(0.001).sleep();
943  spinOnce();
944  }
945 
946  ASSERT_EQ(last_count, helper.total_calls_);
947 }
948 
949 int main(int argc, char** argv)
950 {
951  testing::InitGoogleTest(&argc, argv);
952  ros::init(argc, argv, g_node_name);
953 
954  return RUN_ALL_TESTS();
955 }
956 
d
void callback(const TimerEvent &)
void setPeriod(const WallDuration p, bool reset=false)
TimerHelper(Rate r, bool oneshot=false)
void pretendWork(const float t)
WallTimerHelper(float period, bool oneshot=false)
ROSCPP_DECL void start()
int main(int argc, char **argv)
f
void stop()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int32_t total_calls_
TimerHelper(Duration period, bool oneshot=false)
static void setNow(const Time &new_now)
void callback(const SteadyTimerEvent &e)
int32_t g_steady_count
SteadyTime current_expected
WallDuration expected_period_
void callback(const TimerEvent &)
bool sleep() const
SteadyTimer createSteadyTimer(WallDuration period, void(T::*callback)(const SteadyTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
void steadyTimerCallback(const ros::SteadyTimerEvent &)
TEST(RoscppTimerCallbacks, singleSteadyTimeCallback)
int32_t g_count
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void callback(const WallTimerEvent &e)
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
WallDuration expected_period_
WallTime current_expected
bool sleep()
std::string g_node_name
Duration expected_period_
void timerCallback(const ros::WallTimerEvent &)
SteadyTimerHelper(float period, bool oneshot=false)
static Time now()
void pretendWork(const float t)
void setPeriod(const WallDuration p, bool reset=false)
bool ok() const
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
ros::WallTime t
bool hasPending()


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46