00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <string>
00037 #include <sstream>
00038 #include <fstream>
00039
00040 #include <gtest/gtest.h>
00041
00042 #include <time.h>
00043 #include <stdlib.h>
00044
00045 #include "ros/ros.h"
00046 #include "ros/callback_queue.h"
00047 #include <test_roscpp/TestArray.h>
00048 #include <test_roscpp/TestStringString.h>
00049
00050 #include <boost/scoped_ptr.hpp>
00051
00052 using namespace ros;
00053 using namespace test_roscpp;
00054
00055 std::string g_node_name = "test_timer_callbacks";
00056
00057 class WallTimerHelper
00058 {
00059 public:
00060 WallTimerHelper(float period, bool oneshot = false)
00061 : expected_period_(period)
00062 , failed_(false)
00063 , total_calls_(0)
00064 {
00065 NodeHandle n;
00066 timer_ = n.createWallTimer(expected_period_, &WallTimerHelper::callback, this, oneshot);
00067 }
00068
00069 void callback(const WallTimerEvent& e)
00070 {
00071 bool first = last_call_.isZero();
00072 WallTime last_call = last_call_;
00073 last_call_ = WallTime::now();
00074 WallTime start = last_call_;
00075
00076 if (!first)
00077 {
00078 if (fabsf(expected_next_call_.toSec() - start.toSec()) > 0.1f)
00079 {
00080 ROS_ERROR("Call came at wrong time (%f vs. %f)", expected_next_call_.toSec(), start.toSec());
00081 failed_ = true;
00082 }
00083 }
00084
00085 expected_next_call_ = e.current_expected + expected_period_;
00086
00087 WallTime end = WallTime::now();
00088 last_duration_ = end - start;
00089
00090 ++total_calls_;
00091 }
00092
00093 WallTime last_call_;
00094 WallTime expected_next_call_;
00095 WallDuration expected_period_;
00096 WallDuration last_duration_;
00097
00098 bool failed_;
00099
00100 WallTimer timer_;
00101 int32_t total_calls_;
00102 };
00103
00104 TEST(RoscppTimerCallbacks, singleWallTimeCallback)
00105 {
00106 NodeHandle n;
00107 WallTimerHelper helper1(0.01);
00108
00109 WallDuration d(0.001f);
00110 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00111 {
00112 spinOnce();
00113 d.sleep();
00114 }
00115
00116 if (helper1.failed_)
00117 {
00118 FAIL();
00119 }
00120
00121 if (helper1.total_calls_ < 99)
00122 {
00123 ROS_ERROR("Total calls: %d (expected at least 100)", helper1.total_calls_);
00124 FAIL();
00125 }
00126 }
00127
00128 TEST(RoscppTimerCallbacks, multipleWallTimeCallbacks)
00129 {
00130 NodeHandle n;
00131 const int count = 100;
00132 typedef boost::scoped_ptr<WallTimerHelper> HelperPtr;
00133 HelperPtr helpers[count];
00134 for (int i = 0; i < count; ++i)
00135 {
00136 helpers[i].reset(new WallTimerHelper((float)(i + 1) * 0.1f));
00137 }
00138
00139 WallDuration d(0.01f);
00140 const int spin_count = 1000;
00141 for (int32_t i = 0; i < spin_count && n.ok(); ++i)
00142 {
00143 spinOnce();
00144 d.sleep();
00145 }
00146
00147 for (int i = 0; i < count; ++i)
00148 {
00149 if (helpers[i]->failed_)
00150 {
00151 ROS_ERROR("Helper %d failed", i);
00152 FAIL();
00153 }
00154
00155 int32_t expected_count = (spin_count * d.toSec()) / helpers[i]->expected_period_.toSec();
00156 if (helpers[i]->total_calls_ < (expected_count - 1))
00157 {
00158 ROS_ERROR("Helper %d total calls: %d (at least %d expected)", i, helpers[i]->total_calls_, expected_count);
00159 FAIL();
00160 }
00161 }
00162 }
00163
00164 TEST(RoscppTimerCallbacks, stopWallTimer)
00165 {
00166 NodeHandle n;
00167 WallTimerHelper helper(0.001);
00168
00169 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00170 {
00171 WallDuration(0.001).sleep();
00172 spinOnce();
00173 }
00174
00175 ASSERT_GT(helper.total_calls_, 0);
00176 int32_t last_count = helper.total_calls_;
00177 helper.timer_.stop();
00178
00179 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00180 {
00181 WallDuration(0.001).sleep();
00182 spinOnce();
00183 }
00184
00185 ASSERT_EQ(last_count, helper.total_calls_);
00186 }
00187
00188 int32_t g_count = 0;
00189 void timerCallback(const ros::WallTimerEvent& evt)
00190 {
00191 ++g_count;
00192 }
00193
00194 TEST(RoscppTimerCallbacks, stopThenSpin)
00195 {
00196 g_count = 0;
00197 NodeHandle n;
00198 ros::WallTimer timer = n.createWallTimer(ros::WallDuration(0.001), timerCallback);
00199
00200 WallDuration(0.1).sleep();
00201 timer.stop();
00202
00203 spinOnce();
00204
00205 ASSERT_EQ(g_count, 0);
00206 }
00207
00208 TEST(RoscppTimerCallbacks, oneShotWallTimer)
00209 {
00210 NodeHandle n;
00211 WallTimerHelper helper(0.001, true);
00212
00213 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00214 {
00215 WallDuration(0.001).sleep();
00216 spinOnce();
00217 }
00218
00219 ASSERT_EQ(helper.total_calls_, 1);
00220 }
00221
00222 class TimerHelper
00223 {
00224 public:
00225 TimerHelper(Duration period, bool oneshot = false)
00226 : failed_(false)
00227 , expected_period_(period)
00228 , total_calls_(0)
00229 {
00230 NodeHandle n;
00231 timer_ = n.createTimer(expected_period_, &TimerHelper::callback, this, oneshot);
00232 }
00233
00234 void callback(const TimerEvent& e)
00235 {
00236 ++total_calls_;
00237 }
00238
00239 bool failed_;
00240
00241 Duration expected_period_;
00242
00243 Timer timer_;
00244 int32_t total_calls_;
00245 };
00246
00247 TEST(RoscppTimerCallbacks, singleROSTimeCallback)
00248 {
00249 NodeHandle n;
00250
00251 Time now(1, 0);
00252 Time::setNow(now);
00253
00254 TimerHelper helper(Duration(0, 10000000));
00255
00256 Duration d(0, 1000000);
00257 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00258 {
00259 now += d;
00260 Time::setNow(now);
00261
00262 while (helper.timer_.hasPending())
00263 {
00264 WallDuration(0.001).sleep();
00265 spinOnce();
00266 }
00267 }
00268
00269 if (helper.failed_)
00270 {
00271 FAIL();
00272 }
00273
00274 if (helper.total_calls_ != 100)
00275 {
00276 ROS_ERROR("Total calls: %d (expected 100)", helper.total_calls_);
00277 FAIL();
00278 }
00279 }
00280
00281 TEST(RoscppTimerCallbacks, oneshotROSTimer)
00282 {
00283 NodeHandle n;
00284
00285 Time now(1, 0);
00286 Time::setNow(now);
00287
00288 TimerHelper helper(Duration(0, 10000000), true);
00289
00290 Duration d(0, 1000000);
00291 for (int32_t i = 0; i < 1000 && n.ok(); ++i)
00292 {
00293 now += d;
00294 Time::setNow(now);
00295
00296 while (helper.timer_.hasPending())
00297 {
00298 WallDuration(0.001).sleep();
00299 spinOnce();
00300 }
00301 }
00302
00303 if (helper.failed_)
00304 {
00305 FAIL();
00306 }
00307
00308 ASSERT_EQ(helper.total_calls_, 1);
00309 }
00310
00311 TEST(RoscppTimerCallbacks, singleROSTimeCallbackLargeTimestep)
00312 {
00313 NodeHandle n;
00314
00315 Time now(1, 0);
00316 Time::setNow(now);
00317
00318 TimerHelper helper(Duration(0, 10000000));
00319
00320 Duration d(0, 100000000);
00321 for (int32_t i = 0; i < 100 && n.ok(); ++i)
00322 {
00323 now += d;
00324 Time::setNow(now);
00325
00326 while (helper.timer_.hasPending())
00327 {
00328 WallDuration(0.001).sleep();
00329 spinOnce();
00330 }
00331 }
00332
00333 if (helper.failed_)
00334 {
00335 FAIL();
00336 }
00337
00338 if (helper.total_calls_ != 200)
00339 {
00340 ROS_ERROR("Total calls: %d (expected 200)", helper.total_calls_);
00341 FAIL();
00342 }
00343 }
00344
00345 TEST(RoscppTimerCallbacks, multipleROSTimeCallbacks)
00346 {
00347 NodeHandle n;
00348
00349 Time now(1, 0);
00350 Time::setNow(now);
00351
00352 const int count = 100;
00353 typedef boost::scoped_ptr<TimerHelper> HelperPtr;
00354 HelperPtr helpers[count];
00355 for (int i = 0; i < count; ++i)
00356 {
00357 helpers[i].reset(new TimerHelper(Duration((float)(i + 1) * 0.01f)));
00358 }
00359
00360 Duration d(0.001f);
00361 const int spin_count = 1000;
00362 for (int32_t i = 0; i < spin_count && n.ok(); ++i)
00363 {
00364 now += d;
00365 Time::setNow(now);
00366
00367 bool pending = false;
00368
00369 do
00370 {
00371 pending = false;
00372 for (int i = 0; i < count; ++i)
00373 {
00374 pending |= helpers[i]->timer_.hasPending();
00375 }
00376
00377 WallDuration(0.001).sleep();
00378 spinOnce();
00379 } while (pending);
00380 }
00381
00382 for (int i = 0; i < count; ++i)
00383 {
00384 if (helpers[i]->failed_)
00385 {
00386 ROS_ERROR("Helper %d failed", i);
00387 FAIL();
00388 }
00389
00390 int32_t expected_count = (spin_count * d.toSec()) / helpers[i]->expected_period_.toSec();
00391 if (helpers[i]->total_calls_ < (expected_count - 1) || helpers[i]->total_calls_ > (expected_count + 1))
00392 {
00393 ROS_ERROR("Helper %d total calls: %d (%d expected)", i, helpers[i]->total_calls_, expected_count);
00394 FAIL();
00395 }
00396 }
00397 }
00398
00399 class Tracked
00400 {
00401 public:
00402 Tracked()
00403 {
00404 g_count = 0;
00405 }
00406
00407 void callback(const TimerEvent& e)
00408 {
00409 ++g_count;
00410 }
00411 };
00412
00413 TEST(RoscppTimerCallbacks, trackedObject)
00414 {
00415 NodeHandle n;
00416 Time now(1, 0);
00417 Time::setNow(now);
00418
00419 boost::shared_ptr<Tracked> tracked(new Tracked);
00420 Timer timer = n.createTimer(Duration(0.001), &Tracked::callback, tracked);
00421
00422 now += Duration(0.1);
00423 Time::setNow(now);
00424
00425 while (timer.hasPending())
00426 {
00427 WallDuration(0.001).sleep();
00428 spinOnce();
00429 }
00430
00431 ASSERT_GT(g_count, 0);
00432 int32_t last_count = g_count;
00433 tracked.reset();
00434
00435 now += Duration(0.1);
00436 Time::setNow(now);
00437
00438 while (timer.hasPending())
00439 {
00440 WallDuration(0.001).sleep();
00441 spinOnce();
00442 }
00443
00444 ASSERT_EQ(last_count, g_count);
00445 }
00446
00447 TEST(RoscppTimerCallbacks, stopROSTimer)
00448 {
00449 NodeHandle n;
00450 Time now(1, 0);
00451 Time::setNow(now);
00452
00453 TimerHelper helper(Duration(0.001));
00454
00455 now += Duration(0.1);
00456 Time::setNow(now);
00457
00458 while (helper.timer_.hasPending())
00459 {
00460 WallDuration(0.001).sleep();
00461 spinOnce();
00462 }
00463
00464 ASSERT_GT(helper.total_calls_, 0);
00465 int32_t last_count = helper.total_calls_;
00466 helper.timer_.stop();
00467
00468 now += Duration(0.1);
00469 Time::setNow(now);
00470
00471 while (helper.timer_.hasPending())
00472 {
00473 WallDuration(0.001).sleep();
00474 spinOnce();
00475 }
00476
00477 ASSERT_EQ(last_count, helper.total_calls_);
00478 }
00479
00480 int main(int argc, char** argv)
00481 {
00482 testing::InitGoogleTest(&argc, argv);
00483 ros::init(argc, argv, g_node_name);
00484
00485 return RUN_ALL_TESTS();
00486 }
00487