eventservice_test.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Wed Jan 18 14:11:41 CET 2006  eventservice_test.cpp
00003 
00004                         eventservice_test.cpp -  description
00005                            -------------------
00006     begin                : Wed January 18 2006
00007     copyright            : (C) 2006 Peter Soetens
00008     email                : peter.soetens@mech.kuleuven.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 <Event.hpp>
00022 #include <Logger.hpp>
00023 #include <base/RunnableInterface.hpp>
00024 
00025 #include <EventService.hpp>
00026 #include <internal/DataSourceGenerator.hpp>
00027 
00028 #include "eventservice_test.hpp"
00029 #include <boost/bind.hpp>
00030 #include <boost/scoped_ptr.hpp>
00031 
00032 using namespace RTT;
00033 using namespace boost;
00034 using namespace std;
00035 
00036 
00037 void
00038 EventServiceTest::setUp()
00039 {
00040     t_event0 = Event<void(void)>("t_event0");
00041     t_event1 = RTT::Event<void( std::string )>("t_event1");
00042     t_event2 = RTT::Event<void( std::string, double )>("t_event2");
00043     t_event3 = RTT::Event<void( std::string, double, bool )>("t_event3");
00044 
00045 
00046     event_proc = new EventProcessor();
00047     act.run(event_proc);
00048     act.start();
00049     es = new EventService(event_proc);
00050     reset();
00051 }
00052 
00053 
00054 void
00055 EventServiceTest::tearDown()
00056 {
00057     act.stop();
00058     delete es;
00059     delete event_proc;
00060 }
00061 
00062 void EventServiceTest::listener0(void)
00063 {
00064     t_listener_done = true;
00065 }
00066 
00067 void EventServiceTest::completer0(void)
00068 {
00069     t_completer_done = true;
00070 }
00071 
00072 void EventServiceTest::listener1(const std::string& s)
00073 {
00074     t_listener_done = true;
00075     t_listener_string=s;
00076 }
00077 void EventServiceTest::completer1(const std::string&s)
00078 {
00079     t_completer_done = true;
00080     t_completer_string=s;
00081 }
00082 void EventServiceTest::listener2(const std::string& s, double f )
00083 {
00084     t_listener_done = true;
00085     t_listener_string=s;
00086     t_listener_double=f;
00087 }
00088 void EventServiceTest::completer2(const std::string& s, double f)
00089 {
00090     t_completer_done = true;
00091     t_completer_string=s;
00092     t_completer_double=f;
00093 }
00094 
00095 void EventServiceTest::listener3(std::string s, double f, bool b)
00096 {
00097     t_listener_done = true;
00098     t_listener_string=s;
00099     t_listener_double=f;
00100     t_listener_bool=b;
00101 }
00102 void EventServiceTest::completer3(std::string s, double f, bool b )
00103 {
00104     t_completer_done = true;
00105     t_completer_string=s;
00106     t_completer_double=f;
00107     t_completer_bool=b;
00108 }
00109 
00110 void EventServiceTest::reset()
00111 {
00112     t_listener_done = false;
00113     t_completer_done = false;
00114     t_listener_string = "";
00115     t_listener_double = 0.0;
00116     t_listener_bool = false;
00117     t_completer_string = "";
00118     t_completer_double = 0.0;
00119     t_completer_bool = false;
00120 }
00121 
00122 void EventServiceTest::setup()
00123 {
00124     es->addEvent( &t_event0, "");
00125     es->addEvent( &t_event1, "", "", "" );
00126     es->addEvent( &t_event2, "", "", "", "", "" );
00127     es->addEvent( &t_event3, "", "", "", "", "", "", "" );
00128 }
00129 
00130 void EventServiceTest::cleanup()
00131 {
00132     es->removeEvent( "t_event0" );
00133     es->removeEvent( "t_event1" );
00134     es->removeEvent( "t_event2" );
00135     es->removeEvent( "t_event3" );
00136 }
00137 
00138 // Registers the fixture into the 'registry'
00139 BOOST_FIXTURE_TEST_SUITE(  EventServiceTestSuite,  EventServiceTest )
00140 
00141 BOOST_AUTO_TEST_CASE( testAddRemove )
00142 {
00143     bool result;
00144     result = es->addEvent( &t_event0 );
00145     BOOST_CHECK( result );
00146     result = es->addEvent( &t_event1 );
00147     BOOST_CHECK( result );
00148     result = es->addEvent( &t_event2 );
00149     BOOST_CHECK( result );
00150     result = es->addEvent( &t_event3 );
00151     BOOST_CHECK( result );
00152 
00153     result = es->addEvent( &t_event0 );
00154     BOOST_CHECK( result == false );
00155 
00156     result = es->removeEvent( "t_event0" );
00157     BOOST_CHECK( result );
00158     result = es->removeEvent( "t_event1" );
00159     BOOST_CHECK( result );
00160     result = es->removeEvent( "t_event2" );
00161     BOOST_CHECK( result );
00162     result = es->removeEvent( "t_event3" );
00163     BOOST_CHECK( result );
00164 
00165     result = es->removeEvent( "t_event0" );
00166     BOOST_CHECK( result == false );
00167 }
00168 
00169 BOOST_AUTO_TEST_CASE(  testSetupSyn )
00170 {
00171     this->setup();
00172     Handle h;
00173     h = es->setupSyn("t_event0", bind(&EventServiceTest::listener0,this), vector<DataSourceBase::shared_ptr>() );
00174     BOOST_CHECK( h );
00175     h = es->setupSyn("t_event1", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string)));
00176     BOOST_CHECK( h );
00177     h = es->setupSyn("t_event2", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string), ref(t_listener_double)));
00178     BOOST_CHECK( h );
00179     h = es->setupSyn("t_event3", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string), ref(t_listener_double),ref(t_listener_bool)));
00180     BOOST_CHECK( h );
00181 
00182     this->cleanup();
00183 }
00184 
00185 BOOST_AUTO_TEST_CASE( testSetupAsyn)
00186 {
00187     this->setup();
00188     Handle h;
00189     h = es->setupAsyn("t_event0", bind(&EventServiceTest::completer0,this), vector<DataSourceBase::shared_ptr>(),event_proc );
00190     BOOST_CHECK( h );
00191     h = es->setupAsyn("t_event1", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string)),event_proc);
00192     BOOST_CHECK( h );
00193     h = es->setupAsyn("t_event2", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string), ref(t_completer_double)),event_proc);
00194     BOOST_CHECK( h );
00195     h = es->setupAsyn("t_event3", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string), ref(t_completer_double), ref(t_completer_bool) ),event_proc);
00196     BOOST_CHECK( h );
00197 
00198     this->cleanup();
00199 }
00200 
00201 BOOST_AUTO_TEST_CASE( testSetupEmit)
00202 {
00203     this->setup();
00204 
00205     ActionInterface::shared_ptr r;
00206     r.reset( es->getEvent("t_event0", std::vector<DataSourceBase::shared_ptr>() ) );
00207     BOOST_CHECK( r );
00208     r.reset( es->getEvent("t_event1", GenerateDataSource()(std::string("hello")) ) );
00209     BOOST_CHECK( r );
00210     r.reset( es->getEvent("t_event2", GenerateDataSource()(std::string("hello"),0.1234) ) );
00211     BOOST_CHECK( r );
00212     r.reset( es->getEvent("t_event3", GenerateDataSource()(std::string("hello"),0.1234, true) ) );
00213     BOOST_CHECK( r );
00214 
00215     this->cleanup();
00216 }
00217 
00218 BOOST_AUTO_TEST_CASE( testEmit0)
00219 {
00220     this->setup();
00221 
00222     Handle h1, h2;
00223     h1 = es->setupSyn("t_event0", bind(&EventServiceTest::listener0,this), vector<DataSourceBase::shared_ptr>() );
00224     h2 = es->setupAsyn("t_event0", bind(&EventServiceTest::completer0,this), vector<DataSourceBase::shared_ptr>(),event_proc );
00225     ActionInterface::shared_ptr r;
00226     r.reset( es->getEvent("t_event0", std::vector<DataSourceBase::shared_ptr>() ) );
00227 
00228     BOOST_CHECK( h1.connect() );
00229     r->execute();
00230     BOOST_CHECK( t_listener_done );
00231     this->reset();
00232     BOOST_CHECK( h1.disconnect() );
00233 
00234     BOOST_CHECK( h2.connect() );
00235     r->execute();
00236     BOOST_CHECK( !t_completer_done );
00237     event_proc->step();
00238     BOOST_CHECK( t_completer_done );
00239     this->reset();
00240     BOOST_CHECK( h2.disconnect() );
00241 
00242     this->cleanup();
00243 }
00244 
00245 BOOST_AUTO_TEST_CASE( testEmit1)
00246 {
00247     this->setup();
00248 
00249     Handle h1, h2;
00250     ActionInterface::shared_ptr r;
00251 
00252     h1 = es->setupSyn("t_event1", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string)));
00253     h2 = es->setupAsyn("t_event1", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string)),event_proc);
00254     r.reset( es->getEvent("t_event1", GenerateDataSource()(std::string("hello")) ) );
00255 
00256     BOOST_CHECK( h1.connect() );
00257     r->execute();
00258     BOOST_CHECK( t_listener_done );
00259     BOOST_CHECK( t_listener_string == std::string("hello") );
00260     this->reset();
00261     BOOST_CHECK( h1.disconnect() );
00262 
00263     BOOST_CHECK( h2.connect() );
00264     r->execute();
00265     BOOST_CHECK( !t_completer_done );
00266     event_proc->step();
00267     BOOST_CHECK( t_completer_done );
00268     BOOST_CHECK( t_completer_string == std::string("hello") );
00269     this->reset();
00270     BOOST_CHECK( h2.disconnect() );
00271 
00272     this->cleanup();
00273 }
00274 BOOST_AUTO_TEST_CASE( testEmit2)
00275 {
00276     this->setup();
00277     Handle h1, h2;
00278     ActionInterface::shared_ptr r;
00279 
00280     h1 = es->setupSyn("t_event2", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string), ref(t_listener_double)));
00281     h2 = es->setupAsyn("t_event2", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string), ref(t_completer_double)),event_proc);
00282 
00283     r.reset( es->getEvent("t_event2", GenerateDataSource()(std::string("hello"),0.1234) ) );
00284 
00285 
00286     BOOST_CHECK( h1.connect() );
00287     r->execute();
00288     BOOST_CHECK( t_listener_done );
00289     BOOST_CHECK( t_listener_string == std::string("hello") );
00290     BOOST_CHECK( t_listener_double == 0.1234 );
00291     this->reset();
00292     BOOST_CHECK( h1.disconnect() );
00293 
00294     BOOST_CHECK( h2.connect() );
00295     r->execute();
00296     BOOST_CHECK( !t_completer_done );
00297     event_proc->step();
00298     BOOST_CHECK( t_completer_done );
00299     BOOST_CHECK( t_completer_string == std::string("hello") );
00300     BOOST_CHECK( t_completer_double == 0.1234 );
00301     this->reset();
00302     BOOST_CHECK( h2.disconnect() );
00303 
00304     this->cleanup();
00305 }
00306 
00307 BOOST_AUTO_TEST_CASE( testEmit3)
00308 {
00309     this->setup();
00310     Handle h1, h2;
00311     ActionInterface::shared_ptr r;
00312 
00313     h1 = es->setupSyn("t_event3", bind(&EventServiceTest::listener0,this), GenerateDataSource()(ref(t_listener_string), ref(t_listener_double),ref(t_listener_bool)));
00314     h2 = es->setupAsyn("t_event3", bind(&EventServiceTest::completer0,this), GenerateDataSource()(ref(t_completer_string), ref(t_completer_double), ref(t_completer_bool) ),event_proc);
00315     r.reset( es->getEvent("t_event3", GenerateDataSource()(std::string("hello"),0.1234, true) ) );
00316 
00317 
00318     BOOST_CHECK( h1.connect() );
00319     r->execute();
00320     BOOST_CHECK( t_listener_done );
00321     BOOST_CHECK( t_listener_string == std::string("hello") );
00322     BOOST_CHECK( t_listener_double == 0.1234 );
00323     BOOST_CHECK( t_listener_bool == true );
00324     this->reset();
00325     BOOST_CHECK( h1.disconnect() );
00326 
00327     BOOST_CHECK( h2.connect() );
00328     r->execute();
00329     BOOST_CHECK( !t_completer_done );
00330     event_proc->step();
00331     BOOST_CHECK( t_completer_done );
00332     BOOST_CHECK( t_completer_string == std::string("hello") );
00333     BOOST_CHECK( t_completer_double == 0.1234 );
00334     BOOST_CHECK( t_completer_bool == true );
00335     this->reset();
00336     BOOST_CHECK( h2.disconnect() );
00337 
00338     this->cleanup();
00339 }
00340 
00341 void Foo3(string, double, bool)
00342 {
00343 }
00344 
00345 BOOST_AUTO_TEST_CASE( testEventC)
00346 {
00347     // Test EventC and ConnectionC...
00348     Handle h1, h2, h3;
00349 
00350     this->setup();
00351 
00352     try {
00353         //h1 = es->setupConnection("t_event3").callback( Foo3 ).handle();
00354         h1 = es->setupConnection("t_event3").callback( this, &EventServiceTest::listener3 ).handle();
00355     } catch ( std::exception& e ) {
00356         BOOST_CHECK_MESSAGE( e.what(), false );
00357     }
00358 
00359     try {
00360         h2 = es->setupConnection("t_event3").callback( this, &EventServiceTest::completer3 ,event_proc).handle();
00361     } catch ( std::exception& e ) {
00362         BOOST_CHECK_MESSAGE( e.what(), false );
00363     }
00364 
00365     EventC evc;
00366     bool evcarg = true;
00367     try {
00368         evc = es->setupEmit("t_event3").argC( std::string("hello") ).argC( 0.1234 ).arg( evcarg );
00369     } catch ( std::exception& e ) {
00370         BOOST_CHECK_MESSAGE( e.what(), false );
00371     }
00372 
00373     BOOST_CHECK( h1.connect() );
00374     evc.emit();
00375     BOOST_CHECK( t_listener_done );
00376     BOOST_CHECK( t_listener_string == std::string("hello") );
00377     BOOST_CHECK( t_listener_double == 0.1234 );
00378     BOOST_CHECK( t_listener_bool == evcarg );
00379     this->reset();
00380     BOOST_CHECK( h1.disconnect() );
00381 
00382     BOOST_CHECK( h2.connect() );
00383     evc.emit();
00384     BOOST_CHECK( !t_completer_done );
00385     event_proc->step();
00386     BOOST_CHECK( t_completer_done );
00387     BOOST_CHECK( t_completer_string == std::string("hello") );
00388     BOOST_CHECK( t_completer_double == 0.1234 );
00389     BOOST_CHECK( t_completer_bool == evcarg );
00390     this->reset();
00391     BOOST_CHECK( h2.disconnect() );
00392 
00393     this->cleanup();
00394 
00395 }
00396 
00397 BOOST_AUTO_TEST_SUITE_END()


rtt
Author(s): RTT Developers
autogenerated on Mon Oct 6 2014 03:13:35