40 #include <gtest/gtest.h> 47 #include <test_roscpp/TestArray.h> 48 #include <test_roscpp/TestStringString.h> 50 #include <boost/scoped_ptr.hpp> 64 : expected_period_(period)
67 , testing_period_(false)
68 , calls_before_testing_period_(0)
76 bool first = last_call_.isZero();
84 if (time_error > 5.0 || time_error < -0.01)
95 if(total_calls_ == calls_before_testing_period_)
103 else if(total_calls_ == (calls_before_testing_period_+1))
111 else if(total_calls_ == (calls_before_testing_period_+2))
119 else if(total_calls_ == (calls_before_testing_period_+3))
132 timer_.setPeriod(p, reset);
133 expected_period_ = p;
155 TEST(RoscppTimerCallbacks, singleSteadyTimeCallback)
161 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
179 TEST(RoscppTimerCallbacks, multipleSteadyTimeCallbacks)
182 const int count = 100;
183 typedef boost::scoped_ptr<SteadyTimerHelper> HelperPtr;
184 HelperPtr helpers[count];
185 for (
int i = 0; i < count; ++i)
191 const int spin_count = 1000;
192 for (int32_t i = 0; i < spin_count && n.
ok(); ++i)
198 for (
int i = 0; i < count; ++i)
200 if (helpers[i]->failed_)
206 int32_t expected_count = (spin_count * d.
toSec()) / helpers[i]->expected_period_.toSec();
207 if (helpers[i]->total_calls_ < (expected_count - 1))
209 ROS_ERROR(
"Helper %d total calls: %d (at least %d expected)", i, helpers[i]->total_calls_, expected_count);
215 TEST(RoscppTimerCallbacks, steadySetPeriod)
223 while(helper.total_calls_ < 1)
229 helper.pretendWork(0.1);
235 while(helper.total_calls_ < 2)
241 helper.pretendWork(0.1);
246 while(helper.total_calls_ < 3)
252 helper.pretendWork(0.1);
256 helper.setPeriod(p,
true);
257 while(helper.total_calls_ < 4)
263 helper.pretendWork(0.1);
267 helper.setPeriod(p,
true);
268 while(helper.total_calls_ < 5)
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)
283 helper.testing_period_ =
false;
293 TEST(RoscppTimerCallbacks, stopSteadyTimer)
298 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
308 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
323 TEST(RoscppTimerCallbacks, steadyStopThenSpin)
337 TEST(RoscppTimerCallbacks, oneShotSteadyTimer)
342 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
357 : expected_period_(period)
360 , testing_period_(false)
361 , calls_before_testing_period_(0)
369 bool first = last_call_.isZero();
377 if (time_error > 5.0 || time_error < -0.01)
388 if(total_calls_ == calls_before_testing_period_)
396 else if(total_calls_ == (calls_before_testing_period_+1))
404 else if(total_calls_ == (calls_before_testing_period_+2))
412 else if(total_calls_ == (calls_before_testing_period_+3))
425 timer_.setPeriod(p, reset);
426 expected_period_ = p;
448 TEST(RoscppTimerCallbacks, singleWallTimeCallback)
454 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
472 TEST(RoscppTimerCallbacks, multipleWallTimeCallbacks)
475 const int count = 100;
476 typedef boost::scoped_ptr<WallTimerHelper> HelperPtr;
477 HelperPtr helpers[count];
478 for (
int i = 0; i < count; ++i)
484 const int spin_count = 1000;
485 for (int32_t i = 0; i < spin_count && n.
ok(); ++i)
491 for (
int i = 0; i < count; ++i)
493 if (helpers[i]->failed_)
499 int32_t expected_count = (spin_count * d.
toSec()) / helpers[i]->expected_period_.toSec();
500 if (helpers[i]->total_calls_ < (expected_count - 1))
502 ROS_ERROR(
"Helper %d total calls: %d (at least %d expected)", i, helpers[i]->total_calls_, expected_count);
508 TEST(RoscppTimerCallbacks, setPeriod)
516 while(helper.total_calls_ < 1)
522 helper.pretendWork(0.1);
529 while(helper.total_calls_ < 2)
535 helper.pretendWork(0.1);
541 while(helper.total_calls_ < 3)
547 helper.pretendWork(0.1);
552 helper.setPeriod(p,
true);
553 while(helper.total_calls_ < 4)
559 helper.pretendWork(0.1);
564 helper.setPeriod(p,
true);
565 while(helper.total_calls_ < 5)
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)
580 helper.testing_period_ =
false;
590 TEST(RoscppTimerCallbacks, stopWallTimer)
595 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
605 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
620 TEST(RoscppTimerCallbacks, stopThenSpin)
634 TEST(RoscppTimerCallbacks, oneShotWallTimer)
639 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
653 , expected_period_(period)
662 , expected_period_(r.expectedCycleTime())
682 TEST(RoscppTimerCallbacks, singleROSTimeCallback)
692 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
716 TEST(RoscppTimerCallbacks, singleROSTimeCallbackFromRate)
726 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
750 TEST(RoscppTimerCallbacks, oneshotROSTimer)
760 for (int32_t i = 0; i < 1000 && n.
ok(); ++i)
780 TEST(RoscppTimerCallbacks, singleROSTimeCallbackLargeTimestep)
790 for (int32_t i = 0; i < 100 && n.
ok(); ++i)
814 TEST(RoscppTimerCallbacks, multipleROSTimeCallbacks)
821 const int count = 100;
822 typedef boost::scoped_ptr<TimerHelper> HelperPtr;
823 HelperPtr helpers[count];
824 for (
int i = 0; i < count; ++i)
830 const int spin_count = 1000;
831 for (int32_t i = 0; i < spin_count && n.
ok(); ++i)
836 bool pending =
false;
841 for (
int i = 0; i < count; ++i)
843 pending |= helpers[i]->timer_.hasPending();
851 for (
int i = 0; i < count; ++i)
853 if (helpers[i]->failed_)
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))
862 ROS_ERROR(
"Helper %d total calls: %d (%d expected)", i, helpers[i]->total_calls_, expected_count);
882 TEST(RoscppTimerCallbacks, trackedObject)
913 ASSERT_EQ(last_count,
g_count);
916 TEST(RoscppTimerCallbacks, stopROSTimer)
949 int main(
int argc,
char** argv)
951 testing::InitGoogleTest(&argc, argv);
954 return RUN_ALL_TESTS();
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)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TimerHelper(Duration period, bool oneshot=false)
static void setNow(const Time &new_now)
void callback(const SteadyTimerEvent &e)
SteadyTime current_expected
WallDuration expected_period_
void callback(const TimerEvent &)
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)
int calls_before_testing_period_
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
Duration expected_period_
void timerCallback(const ros::WallTimerEvent &)
SteadyTimerHelper(float period, bool oneshot=false)
void pretendWork(const float t)
void setPeriod(const WallDuration p, bool reset=false)
int calls_before_testing_period_
ROSCPP_DECL void spinOnce()