time_test.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Fri Feb 11 15:59:13 CET 2005  time_test.cpp
00003 
00004                         time_test.cpp -  description
00005                            -------------------
00006     begin                : Fri February 11 2005
00007     copyright            : (C) 2005 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.ac.be
00009 
00010  ***************************************************************************
00011  *                                                                         *
00012  *   This program is free software; you can redistribute it and/or modify  *
00013  *   it under the terms of the GNU General Public License as published by  *
00014  *   the Free Software Foundation; either version 2 of the License, or     *
00015  *   (at your option) any later version.                                   *
00016  *                                                                         *
00017  ***************************************************************************/
00018 
00019 #include "unit.hpp"
00020 
00021 #include "time_test.hpp"
00022 #include <boost/bind.hpp>
00023 #include <os/Timer.hpp>
00024 #include <rtt-detail-fwd.hpp>
00025 #include <iostream>
00026 
00027 #define EPSILON 0.000000002
00028 
00029 // Registers the fixture into the 'registry'
00030 //CPPUNIT_TEST_SUITE_REGISTRATION( TimeTest );
00031 
00032 using namespace std;
00033 using namespace RTT;
00034 using namespace RTT::detail;
00035 using namespace boost;
00036 
00037 TimeTest::TimeTest()
00038 {
00039     hbg = TimeService::Instance();
00040     long_ns = 9007199254740992LL;       // == 2^53
00041     //long_ns = 4503599627370496LL;       // == 2^52
00042     //long_ns = 123456789123456789LL; // 1.234...e17 ns == approx 4 years, but double can not represent this.
00043     long_S  = 9007199.254740992;
00044     //long_S  = 4.503599627370496e14;
00045     normal_ns = 1000000000; // 1s
00046     normal_S = 1.0; // 1s
00047     small_ns = 10;  //  10ns
00048     small_S = 10e-9; //  10ns
00049     small_t = 10;
00050     normal_t = 1000000000; // 1e9 ticks
00051     long_t  = long_ns;     // == 2^53
00052 }
00053 
00054 TimeTest::~TimeTest()
00055 {
00056     hbg->enableSystemClock( true );
00057 }
00058 
00059 struct TestTimer
00060     : public Timer
00061 {
00062     std::vector< std::pair<Timer::TimerId, Seconds> > occured;
00063     TimeService::Seconds mstart;
00064     boost::function<void(Timer::TimerId)> mcallback;
00065     TestTimer()
00066         :Timer(32, ORO_SCHED_RT, os::HighestPriority)
00067     {
00068         occured.reserve(100);
00069         mstart = TimeService::Instance()->secondsSince(0);
00070     }
00071     void timeout(Timer::TimerId id)
00072     {
00073         Seconds now = TimeService::Instance()->secondsSince( 0 );
00074         occured.push_back( std::make_pair(id, now) );
00075         //cout << "Occured: "<< id <<" on " << now - mstart <<"\n";
00076 
00077         if (mcallback) {
00078             mcallback(id);
00079             mcallback = NULL;
00080         }
00081     }
00082 
00083     ~TestTimer()
00084     {
00085         cout.flush();
00086     }
00087 };
00088 
00089 BOOST_FIXTURE_TEST_SUITE( TimeTestSuite, TimeTest )
00090 
00091 BOOST_AUTO_TEST_CASE( testSecondsConversion )
00092 {
00093     // Test one way
00094     BOOST_REQUIRE_EQUAL( long_ns  , Seconds_to_nsecs(long_S)  );
00095     BOOST_REQUIRE_EQUAL( normal_ns, Seconds_to_nsecs(normal_S));
00096     BOOST_REQUIRE_EQUAL( small_ns , Seconds_to_nsecs(small_S) );
00097 
00098     // Test other way
00099     BOOST_REQUIRE_EQUAL( long_S  , nsecs_to_Seconds(long_ns));
00100     BOOST_REQUIRE_EQUAL( normal_S, nsecs_to_Seconds(normal_ns));
00101     BOOST_REQUIRE_EQUAL( small_S , nsecs_to_Seconds(small_ns));
00102 
00103     // Test invariance of conversions :
00104     BOOST_REQUIRE_EQUAL( long_ns  , Seconds_to_nsecs( nsecs_to_Seconds(long_ns) ));
00105     BOOST_REQUIRE_EQUAL( normal_ns, Seconds_to_nsecs( nsecs_to_Seconds(normal_ns) ));
00106     BOOST_REQUIRE_EQUAL( small_ns , Seconds_to_nsecs( nsecs_to_Seconds(small_ns) ));
00107     BOOST_REQUIRE_EQUAL( long_S  , nsecs_to_Seconds( Seconds_to_nsecs(long_S) ));
00108     BOOST_REQUIRE_EQUAL( normal_S, nsecs_to_Seconds( Seconds_to_nsecs(normal_S) ));
00109     BOOST_REQUIRE_EQUAL( small_S , nsecs_to_Seconds( Seconds_to_nsecs(small_S) ));
00110 }
00111 
00112 BOOST_AUTO_TEST_CASE( testTicksConversion )
00113 {
00114     // Test ticks conversion invariance :
00115     // margin is in % rounding error.
00116     int margin = 1;
00117 //#if defined( OROCOS_TARGET_LXRT) || defined(OROCOS_TARGET_XENOMAI)
00118 //    int small_margin = 25; // 25% of 8ns : allow a two-off.
00119 //#else
00120 //    int small_margin = 10; // 10% of 8ns : allow a one-off.
00121 //#endif
00122 
00123     // I'm removing the small conversions because they test more the underlying RTOS than Orocos and the underlying RTOS
00124     // isn't fixing this for years...
00125     BOOST_REQUIRE_CLOSE( (double)long_ns  , (double)TimeService::ticks2nsecs( TimeService::nsecs2ticks( long_ns )), margin );
00126     BOOST_REQUIRE_CLOSE( (double)normal_ns, (double)TimeService::ticks2nsecs( TimeService::nsecs2ticks( normal_ns )), margin );
00127     //BOOST_REQUIRE_CLOSE( (double)small_ns , (double)TimeService::ticks2nsecs( TimeService::nsecs2ticks( small_ns )), small_margin );
00128     BOOST_REQUIRE_CLOSE( (double)long_t  , (double)TimeService::nsecs2ticks( TimeService::ticks2nsecs( long_t )), margin );
00129     BOOST_REQUIRE_CLOSE( (double)normal_t, (double)TimeService::nsecs2ticks( TimeService::ticks2nsecs( normal_t )), margin );
00130     //BOOST_REQUIRE_CLOSE( (double)small_t , (double)TimeService::nsecs2ticks( TimeService::ticks2nsecs( small_t )), small_margin );
00131 }
00132 
00133 BOOST_AUTO_TEST_CASE( testTimeProgress )
00134 {
00135     // A time measurement takes time :
00136     TimeService::ticks t = hbg->getTicks();
00137     usleep(100000);
00138     BOOST_CHECK( t !=  hbg->getTicks() );
00139     BOOST_CHECK( 0 !=  hbg->ticksSince(t) );
00140     BOOST_CHECK( 0 !=  hbg->secondsSince(t) );
00141 
00142     // With Re-init of t :
00143     t = 0;
00144     BOOST_REQUIRE_EQUAL( TimeService::ticks(0) , hbg->getTicks( t ) );
00145     t = 0;
00146     // BOOST_REQUIRE_EQUAL( Seconds(0.0) , hbg->getSeconds( t ) );
00147 
00148     // Stop Time Progress:
00149     hbg->enableSystemClock( false );
00150     t = hbg->getTicks();
00151     BOOST_REQUIRE_EQUAL( t ,  hbg->getTicks() );
00152     BOOST_REQUIRE_EQUAL( TimeService::ticks(0) ,  hbg->ticksSince(t) );
00153     // BOOST_REQUIRE_EQUAL( Seconds(0.0) ,  hbg->secondsSince(t) );
00154 
00155     Seconds change_S  = 0.123456789;
00156 
00157     hbg->secondsChange( change_S );
00158     BOOST_CHECK( t !=  hbg->getTicks() ); // ticks must have changed
00159     BOOST_CHECK( -EPSILON < (change_S - hbg->secondsSince(t)) &&
00160                      EPSILON > (change_S - hbg->secondsSince(t)) );
00161 
00162     // Restart Time Progress
00163     hbg->enableSystemClock( true );
00164     BOOST_CHECK( t !=  hbg->getTicks() );
00165     BOOST_CHECK( TimeService::ticks(0) !=  hbg->ticksSince(t) );
00166     BOOST_CHECK( Seconds(0.0) !=  hbg->secondsSince(t) );
00167 
00168 }
00169 
00170 BOOST_AUTO_TEST_CASE( testTimers )
00171 {
00172     TestTimer timer;
00173     Seconds now = hbg->secondsSince( 0 );
00174     // Test arming
00175     BOOST_CHECK( timer.arm(0, 0.5) );
00176     BOOST_CHECK( timer.arm(1, 0.6) );
00177     BOOST_CHECK( timer.arm(2, 0.5) );
00178 
00179     BOOST_CHECK( timer.arm(3, 0.8) );
00180     BOOST_CHECK( timer.arm(3, 0.9) );
00181 
00182     BOOST_CHECK( timer.isArmed( 0 ) );
00183     BOOST_CHECK( timer.isArmed( 1 ) );
00184     BOOST_CHECK( timer.isArmed( 2 ) );
00185     BOOST_CHECK( timer.isArmed( 3 ) );
00186 
00187     sleep(2);
00188 
00189     // Test clearing
00190     BOOST_CHECK( !timer.isArmed( 0 ) );
00191     BOOST_CHECK( !timer.isArmed( 1 ) );
00192     BOOST_CHECK( !timer.isArmed( 2 ) );
00193     BOOST_CHECK( !timer.isArmed( 3 ) );
00194 
00195     // Test sequence
00196     BOOST_CHECK( timer.occured.size() == 4 );
00197     BOOST_CHECK( timer.occured[0].first == 0 );
00198     BOOST_CHECK( timer.occured[1].first == 2 );
00199     BOOST_CHECK( timer.occured[2].first == 1 );
00200     BOOST_CHECK( timer.occured[3].first == 3 );
00201 
00202     // Test timeliness
00203     BOOST_REQUIRE_CLOSE( timer.occured[0].second, now+0.5, 0.1 );
00204     BOOST_REQUIRE_CLOSE( timer.occured[1].second, now+0.5, 0.1 );
00205     BOOST_REQUIRE_CLOSE( timer.occured[2].second, now+0.6, 0.1 );
00206     BOOST_REQUIRE_CLOSE( timer.occured[3].second, now+0.9, 0.1 );
00207 
00208     // Test wrong parameters.
00209     BOOST_CHECK( timer.arm(4, -0.1) == false);
00210     BOOST_CHECK( timer.arm(32, 0.1) == false);
00211 
00212     timer.occured.clear();
00213 
00214     // Test resize.
00215     BOOST_CHECK( timer.arm(10, 0.5) );
00216     timer.setMaxTimers( 5 ); // clears the timer
00217     sleep(1);
00218     BOOST_CHECK( timer.occured.size() == 0 );
00219 }
00220 
00221 BOOST_AUTO_TEST_CASE( testTimerPeriod )
00222 {
00223     TestTimer timer;
00224     Seconds now = hbg->secondsSince( 0 );
00225     // Test starting periodics
00226     BOOST_CHECK( timer.startTimer(0, 0.1) );
00227     BOOST_CHECK( timer.startTimer(1, 0.6) );
00228     BOOST_CHECK( timer.startTimer(2, 0.5) );
00229 
00230     BOOST_CHECK( timer.startTimer(3, 0.5) );
00231     BOOST_CHECK( timer.startTimer(3, 0.2) );
00232 
00233     BOOST_CHECK( timer.isArmed( 0 ) );
00234     BOOST_CHECK( timer.isArmed( 1 ) );
00235     BOOST_CHECK( timer.isArmed( 2 ) );
00236     BOOST_CHECK( timer.isArmed( 3 ) );
00237 
00238     sleep(2);
00239 
00240     // Test clearing
00241     BOOST_CHECK( timer.killTimer( 0 ) );
00242     BOOST_CHECK( timer.killTimer( 1 ) );
00243     BOOST_CHECK( timer.killTimer( 2 ) );
00244     BOOST_CHECK( timer.killTimer( 3 ) );
00245     BOOST_CHECK( !timer.isArmed( 0 ) );
00246     BOOST_CHECK( !timer.isArmed( 1 ) );
00247     BOOST_CHECK( !timer.isArmed( 2 ) );
00248     BOOST_CHECK( !timer.isArmed( 3 ) );
00249 
00250     // Test sequence
00251     //BOOST_CHECK( timer.occured.size() == 4 ); hard to estimate
00252     BOOST_CHECK( timer.occured[0].first == 0 );
00253     BOOST_CHECK( timer.occured[1].first == 0 );
00254     BOOST_CHECK( timer.occured[2].first == 3 );
00255     BOOST_CHECK( timer.occured[3].first == 0 );
00256     BOOST_CHECK( timer.occured[4].first == 0 );
00257     BOOST_CHECK( timer.occured[5].first == 3 );
00258 
00259     BOOST_CHECK( timer.occured[6].first == 0 );
00260     BOOST_CHECK( timer.occured[7].first == 2 );
00261 
00262     BOOST_CHECK( timer.occured[8].first == 0 );
00263     BOOST_CHECK( timer.occured[9].first == 1 );
00264     BOOST_CHECK( timer.occured[10].first == 3 );
00265     BOOST_CHECK( timer.occured[11].first == 0 );
00266     BOOST_CHECK( timer.occured[12].first == 0 );
00267     BOOST_CHECK( timer.occured[13].first == 3 );
00268     BOOST_CHECK( timer.occured[14].first == 0 );
00269 
00270     // Test timeliness
00271     BOOST_REQUIRE_CLOSE( timer.occured[0].second, now+0.1, 0.1 );
00272     BOOST_REQUIRE_CLOSE( timer.occured[1].second, now+0.2, 0.1 );
00273     BOOST_REQUIRE_CLOSE( timer.occured[2].second, now+0.2, 0.1 );
00274     BOOST_REQUIRE_CLOSE( timer.occured[3].second, now+0.3, 0.1 );
00275     BOOST_REQUIRE_CLOSE( timer.occured[4].second, now+0.4, 0.1 );
00276     BOOST_REQUIRE_CLOSE( timer.occured[5].second, now+0.4, 0.1 );
00277     BOOST_REQUIRE_CLOSE( timer.occured[6].second, now+0.5, 0.1 );
00278     BOOST_REQUIRE_CLOSE( timer.occured[7].second, now+0.5, 0.1 );
00279     BOOST_REQUIRE_CLOSE( timer.occured[8].second, now+0.6, 0.1 );
00280     BOOST_REQUIRE_CLOSE( timer.occured[9].second, now+0.6, 0.1 );
00281     BOOST_REQUIRE_CLOSE( timer.occured[10].second, now+0.6, 0.1 );
00282     BOOST_REQUIRE_CLOSE( timer.occured[11].second, now+0.7, 0.1 );
00283     BOOST_REQUIRE_CLOSE( timer.occured[12].second, now+0.8, 0.1 );
00284     BOOST_REQUIRE_CLOSE( timer.occured[13].second, now+0.8, 0.1 );
00285     BOOST_REQUIRE_CLOSE( timer.occured[14].second, now+0.9, 0.1 );
00286 
00287     // Test wrong parameters.
00288     BOOST_CHECK( timer.startTimer(4, -0.1) == false);
00289     BOOST_CHECK( timer.startTimer(500, 0.1) == false);
00290 
00291     timer.occured.clear();
00292 
00293     // Test resize.
00294     BOOST_CHECK( timer.startTimer(10, 0.5) );
00295     timer.setMaxTimers( 5 ); // clears the timer
00296     sleep(1);
00297     BOOST_CHECK( timer.occured.size() == 0 );
00298 }
00299 
00300 BOOST_AUTO_TEST_CASE( testTimerWaitFor )
00301 {
00302     TestTimer timer;
00303     Seconds now = hbg->secondsSince( 0 );
00304 
00305     // Test waitFor
00306     BOOST_CHECK( timer.arm(0, 1.0) );
00307     BOOST_CHECK( timer.isArmed( 0 ) == true );
00308     BOOST_CHECK( timer.waitFor( 0 ) == true );
00309     BOOST_CHECK( timer.isArmed( 0 ) == false );
00310     BOOST_REQUIRE_CLOSE( hbg->secondsSince(0), now + 1.0, 0.1 );
00311 
00312     // Test waitForUntil
00313     now = hbg->secondsSince( 0 );
00314     BOOST_CHECK( timer.arm(0, 1.0) );
00315     BOOST_CHECK( timer.isArmed( 0 ) == true );
00316     BOOST_CHECK( timer.waitForUntil(0, hbg->getNSecs() + RTT::Seconds_to_nsecs(0.5) ) == false );
00317     BOOST_CHECK( timer.isArmed( 0 ) == true );
00318     BOOST_REQUIRE_CLOSE( hbg->secondsSince( 0 ), now + 0.5, 0.1 );
00319     sleep(1);
00320     BOOST_CHECK( timer.isArmed( 0 ) == false );
00321 
00322     // Test killing of one timer
00323     now = hbg->secondsSince( 0 );
00324     BOOST_CHECK( timer.arm(0, 1.0) );
00325     BOOST_CHECK( timer.isArmed( 0 ) );
00326     // program timer 1 to kill timer 0 after 0.5 seconds
00327     timer.mcallback = boost::bind(&Timer::killTimer, &timer, 0);
00328     BOOST_CHECK( timer.arm(1, 0.5) );
00329     BOOST_CHECK( timer.isArmed( 1 ) );
00330     // wait for timer 0
00331     BOOST_CHECK( timer.waitFor( 0 ) );
00332     // callback killed timer 1
00333     BOOST_CHECK( timer.isArmed( 0 ) == false );
00334     BOOST_CHECK( timer.isArmed( 1 ) == false );
00335     BOOST_REQUIRE_CLOSE( hbg->secondsSince(0), now + 0.5, 0.1 );
00336 
00337     // Test stopping the timer thread while another thread is waiting
00338     now = hbg->secondsSince( 0 );
00339     BOOST_CHECK( timer.arm(0, 1.0) );
00340     BOOST_CHECK( timer.isArmed( 0 ) );
00341     // program timer 1 to stop the timer activity after 0.5 seconds
00342     timer.mcallback = boost::bind(&ActivityInterface::stop, timer.getActivity());
00343     BOOST_CHECK( timer.arm(1, 0.5) );
00344     BOOST_CHECK( timer.isArmed( 1 ) );
00345     // wait for timer 0
00346     BOOST_CHECK( timer.waitFor( 0 ) );
00347     // callback stopped the timer activity and waitFor(0) should have returned
00348     BOOST_CHECK( timer.isArmed( 0 ) == false );
00349     BOOST_CHECK( timer.isArmed( 1 ) == false );
00350     BOOST_REQUIRE_CLOSE( hbg->secondsSince(0), now + 0.5, 0.1 );
00351 }
00352 
00353 BOOST_AUTO_TEST_SUITE_END()


rtt
Author(s): RTT Developers
autogenerated on Sat Jun 8 2019 18:46:33