corba_test.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002   tag: Peter Soetens  Mon Jun 26 13:26:02 CEST 2006  generictask_test.cpp
00003 
00004                         generictask_test.cpp -  description
00005                            -------------------
00006     begin                : Mon June 26 2006
00007     copyright            : (C) 2006 Peter Soetens
00008     email                : peter.soetens@fmtc.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 
00020 
00021 #include "unit.hpp"
00022 
00023 #include <transports/corba/corba.h>
00024 #include <rtt/InputPort.hpp>
00025 #include <rtt/OutputPort.hpp>
00026 #include <rtt/OperationCaller.hpp>
00027 #include <rtt/TaskContext.hpp>
00028 #include <transports/corba/TaskContextServer.hpp>
00029 #include <transports/corba/TaskContextProxy.hpp>
00030 #include <rtt/Service.hpp>
00031 #include <rtt/transports/corba/DataFlowI.h>
00032 #include <rtt/transports/corba/RemotePorts.hpp>
00033 #include <transports/corba/ServiceC.h>
00034 #include <transports/corba/CorbaLib.hpp>
00035 
00036 #include "operations_fixture.hpp"
00037 
00038 using namespace std;
00039 using corba::TaskContextProxy;
00040 
00041 class CorbaTest : public OperationsFixture
00042 {
00043 public:
00044     CorbaTest() :
00045         pint1("pint1", "", 3), pdouble1(new Property<double>("pdouble1", "", -3.0)),
00046         aint1(3), adouble1(-3.0), wait(0)
00047     {
00048     // connect DataPorts
00049         mi1 = new InputPort<double> ("mi");
00050         mo1 = new OutputPort<double> ("mo");
00051 
00052         mi2 = new InputPort<double> ("mi");
00053         mo2 = new OutputPort<double> ("mo");
00054 
00055         tc->ports()->addEventPort(*mi1);
00056         tc->ports()->addPort(*mo1);
00057 
00058         t2 = new TaskContext("local");
00059         t2->ports()->addEventPort(*mi2,boost::bind(&CorbaTest::new_data_listener, this, _1));
00060         t2->ports()->addPort(*mo2);
00061 
00062         ts2 = ts = 0;
00063         tp2 = tp = 0;
00064 
00065         // store nested properties:
00066         tc->provides()->addProperty(pint1);
00067         storeProperty(*tc->provides()->properties(), "s1.s2", pdouble1 );
00068 
00069         tc->addAttribute("aint1", aint1);
00070         tc->addAttribute("adouble1", adouble1);
00071     }
00072     ~CorbaTest()
00073     {
00074         delete tp;
00075         delete ts;
00076         delete tp2;
00077         delete ts2;
00078         delete t2;
00079 
00080         delete mi1;
00081         delete mo1;
00082         delete mi2;
00083         delete mo2;
00084     }
00085 
00086     TaskContext* t2;
00087     TaskContext* tp;
00088     corba::TaskContextServer* ts;
00089     TaskContext* tp2;
00090     corba::TaskContextServer* ts2;
00091 
00092     base::PortInterface* signalled_port;
00093     void new_data_listener(base::PortInterface* port);
00094 
00095     // Ports
00096     InputPort<double>*  mi1;
00097     OutputPort<double>* mo1;
00098     InputPort<double>*  mi2;
00099     OutputPort<double>* mo2;
00100 
00101     Property<int> pint1;
00102     Property<double>* pdouble1;
00103 
00104     int aint1;
00105     double adouble1;
00106     int wait;
00107 
00108     // helper test functions
00109     void testPortDataConnection();
00110     void testPortBufferConnection();
00111     void testPortDisconnected();
00112 };
00113 
00114 void CorbaTest::new_data_listener(base::PortInterface* port)
00115 {
00116     signalled_port = port;
00117 }
00118 
00119 
00120 #define ASSERT_PORT_SIGNALLING(code, read_port) \
00121     signalled_port = 0; wait = 0;\
00122     code; \
00123     while (read_port != signalled_port && wait++ != 5) \
00124     usleep(100000); \
00125     BOOST_CHECK( read_port == signalled_port );
00126 
00127 bool wait_for_helper;
00128 #define wait_for( cond, times ) \
00129     wait = 0; \
00130     while( (wait_for_helper = !(cond)) && wait++ != times ) \
00131       usleep(100000); \
00132     if (wait_for_helper) BOOST_CHECK( cond );
00133 
00134 #define wait_for_equal( a, b, times ) \
00135     wait = 0; \
00136     while( (wait_for_helper = ((a) != (b))) && wait++ != times ) \
00137       usleep(100000); \
00138     if (wait_for_helper) BOOST_CHECK_EQUAL( a, b );
00139 
00140 void CorbaTest::testPortDataConnection()
00141 {
00142     // This test assumes that there is a data connection mo1 => mi2
00143     // Check if connection succeeded both ways:
00144     BOOST_CHECK( mo1->connected() );
00145     BOOST_CHECK( mi2->connected() );
00146 
00147     double value = 0;
00148 
00149     // Check if no-data works
00150     BOOST_CHECK_EQUAL( mi2->read(value), NoData );
00151 
00152     // Check if writing works (including signalling)
00153     ASSERT_PORT_SIGNALLING(mo1->write(1.0), mi2)
00154     BOOST_CHECK( mi2->read(value) );
00155     BOOST_CHECK_EQUAL( 1.0, value );
00156     ASSERT_PORT_SIGNALLING(mo1->write(2.0), mi2);
00157     BOOST_CHECK( mi2->read(value) );
00158     BOOST_CHECK_EQUAL( 2.0, value );
00159 }
00160 
00161 void CorbaTest::testPortBufferConnection()
00162 {
00163     // This test assumes that there is a buffer connection mo1 => mi2 of size 3
00164     // Check if connection succeeded both ways:
00165     BOOST_CHECK( mo1->connected() );
00166     BOOST_CHECK( mi2->connected() );
00167 
00168     double value = 0;
00169 
00170     // Check if no-data works
00171     BOOST_CHECK_EQUAL( mi2->read(value), NoData );
00172 
00173     // Check if writing works
00174     ASSERT_PORT_SIGNALLING(mo1->write(1.0), mi2);
00175     ASSERT_PORT_SIGNALLING(mo1->write(2.0), mi2);
00176     ASSERT_PORT_SIGNALLING(mo1->write(3.0), mi2);
00177     BOOST_CHECK( mi2->read(value) );
00178     BOOST_CHECK_EQUAL( 1.0, value );
00179     BOOST_CHECK( mi2->read(value) );
00180     BOOST_CHECK_EQUAL( 2.0, value );
00181     BOOST_CHECK( mi2->read(value) );
00182     BOOST_CHECK_EQUAL( 3.0, value );
00183     BOOST_CHECK_EQUAL( mi2->read(value), OldData );
00184 }
00185 
00186 void CorbaTest::testPortDisconnected()
00187 {
00188     BOOST_CHECK( !mo1->connected() );
00189     BOOST_CHECK( !mi2->connected() );
00190 }
00191 
00192 
00193 // Registers the fixture into the 'registry'
00194 BOOST_FIXTURE_TEST_SUITE(  CorbaTestSuite,  CorbaTest )
00195 
00196 BOOST_AUTO_TEST_CASE( testAttributes )
00197 {
00198     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00199     BOOST_CHECK( ts );
00200     tp = corba::TaskContextProxy::Create( ts->server(), true );
00201     BOOST_CHECK( tp );
00202 
00203     BOOST_CHECK( tp->provides()->hasAttribute("aint1") );
00204     Attribute<int> proxy_int = tp->provides()->getAttribute("aint1");
00205     BOOST_REQUIRE( proxy_int.ready() );
00206 
00207     // initial read through get:
00208     BOOST_CHECK_EQUAL( proxy_int.get(), 3);
00209     // reading through set:
00210     aint1 = 4;
00211     BOOST_CHECK_EQUAL( proxy_int.set(), 4);
00212     // doing remote set:
00213     proxy_int.set( 5 );
00214     BOOST_CHECK_EQUAL( aint1, 5);
00215 
00216     BOOST_CHECK( tp->provides()->hasAttribute("adouble1") );
00217     Attribute<double> proxy_double = tp->provides()->getAttribute("adouble1");
00218     BOOST_REQUIRE( proxy_double.ready() );
00219 
00220     // initial reading through set:
00221     BOOST_CHECK_EQUAL( proxy_double.set(), -3.0 );
00222     // doing remote set, check local and remote result:
00223     proxy_double.set( 5.0 );
00224     BOOST_CHECK_EQUAL( adouble1, 5.0 );
00225     BOOST_CHECK_EQUAL( proxy_double.get(), 5.0);
00226     adouble1 = 6.0;
00227     // reading changed remote:
00228     BOOST_CHECK_EQUAL( proxy_double.get(), 6.0);
00229 }
00230 
00231 BOOST_AUTO_TEST_CASE( testProperties )
00232 {
00233     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00234     BOOST_CHECK( ts );
00235     tp = corba::TaskContextProxy::Create( ts->server(), true );
00236     BOOST_CHECK( tp );
00237 
00238     BOOST_CHECK( findProperty( *tp->provides()->properties(), "pint1") );
00239     Property<int> proxy_int = findProperty( *tp->provides()->properties(), "pint1");
00240     BOOST_REQUIRE( proxy_int.ready() );
00241     // initial read through get:
00242     BOOST_CHECK_EQUAL( proxy_int.get(), 3);
00243     // reading through set:
00244     pint1 = 4;
00245     BOOST_CHECK_EQUAL( proxy_int.set(), 4);
00246     // doing remote set:
00247     proxy_int.set( 5 );
00248     BOOST_CHECK_EQUAL( pint1, 5);
00249 
00250     BOOST_CHECK( findProperty( *tp->provides()->properties(), "s1.s2.pdouble1") );
00251     Property<double> proxy_d = findProperty( *tp->provides()->properties(), "s1.s2.pdouble1");
00252     BOOST_REQUIRE( proxy_d.ready() );
00253     // initial reading through set:
00254     BOOST_CHECK_EQUAL( proxy_d.set(), -3.0 );
00255     // doing remote set, check local and remote result:
00256     proxy_d.set( 5.0 );
00257     BOOST_CHECK_EQUAL( pdouble1->get(), 5.0 );
00258     BOOST_CHECK_EQUAL( proxy_d.get(), 5.0);
00259     pdouble1->set( 6.0 );
00260     // reading changed remote:
00261     BOOST_CHECK_EQUAL( proxy_d.get(), 6.0);
00262 }
00263 
00264 BOOST_AUTO_TEST_CASE( testOperationCallerC_Call )
00265 {
00266 
00267     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00268     BOOST_CHECK( ts );
00269     tp = corba::TaskContextProxy::Create( ts->server(), true );
00270     BOOST_CHECK( tp );
00271 
00272     // This test tests 'transparant' remote invocation of Orocos internal::OperationCallerC objects.
00273     internal::OperationCallerC mc;
00274     double r = 0.0;
00275     mc = tp->provides("methods")->create("vm0", tc->engine() );
00276     BOOST_CHECK( mc.call() );
00277     BOOST_CHECK( r == 0.0 );
00278 
00279     mc = tp->provides("methods")->create("m0", tc->engine() ).ret( r );
00280     BOOST_CHECK( mc.call() );
00281     BOOST_CHECK( r == -1.0 );
00282 
00283     mc = tp->provides("methods")->create("m2", tc->engine() ).argC(1).argC(2.0).ret( r );
00284     BOOST_CHECK( mc.call() );
00285     BOOST_CHECK( r == -3.0 );
00286 
00287     mc = tp->provides("methods")->create("m3", tc->engine() ).ret( r ).argC(1).argC(2.0).argC(true);
00288     BOOST_CHECK( mc.call() );
00289     BOOST_CHECK( r == -4.0 );
00290 
00291     mc = tp->provides("methods")->create("m0except", tc->engine() );
00292     BOOST_CHECK_THROW( mc.call(), std::runtime_error );
00293     BOOST_REQUIRE( tc->inException() );
00294 }
00295 
00296 BOOST_AUTO_TEST_CASE( testOperationCallerC_Send )
00297 {
00298 
00299     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00300     BOOST_CHECK( ts );
00301     tp = corba::TaskContextProxy::Create( ts->server(), true );
00302     BOOST_CHECK( tp );
00303 
00304     OperationCallerC mc;
00305     SendHandleC shc;
00306     double r = 0.0;
00307     double cr = 0.0;
00308     mc = tp->provides("methods")->create("m0", caller->engine()).ret( r );
00309     BOOST_CHECK_NO_THROW( mc.check() );
00310     shc = mc.send();
00311     shc.arg(cr);
00312     BOOST_CHECK( shc.ready() ); // 1 argument to collect.
00313     BOOST_CHECK_NO_THROW( shc.check() );
00314     // now collect:
00315     BOOST_CHECK_EQUAL( shc.collect(), SendSuccess);
00316     BOOST_CHECK_EQUAL( r, 0.0 );
00317     BOOST_CHECK_EQUAL( cr, -1.0 );
00318 
00319     mc = tp->provides("methods")->create("m2", caller->engine()).argC(1).argC(2.0).ret( r );
00320     BOOST_CHECK_NO_THROW( mc.check() );
00321     shc = mc.send();
00322     shc.arg(cr);
00323     BOOST_CHECK( shc.ready() ); // 1 argument to collect.
00324     BOOST_CHECK_NO_THROW( shc.check() );
00325     // now collect:
00326     BOOST_CHECK_EQUAL( shc.collect(), SendSuccess);
00327     BOOST_CHECK_EQUAL( r, 0.0 );
00328     BOOST_CHECK_EQUAL( cr, -3.0 );
00329 
00330     mc = tp->provides("methods")->create("m3", caller->engine()).ret( r ).argC(1).argC(2.0).argC(true);
00331     BOOST_CHECK_NO_THROW( mc.check() );
00332     shc = mc.send();
00333     shc.arg(cr);
00334     BOOST_CHECK( shc.ready() ); // 1 argument to collect.
00335     BOOST_CHECK_NO_THROW( shc.check() );
00336     // now collect:
00337     BOOST_CHECK_EQUAL( shc.collect(), SendSuccess);
00338     BOOST_CHECK_EQUAL( r, 0.0 );
00339     BOOST_CHECK_EQUAL( cr, -4.0 );
00340 
00341     mc = tp->provides("methods")->create("m4", caller->engine()).ret( r ).argC(1).argC(2.0).argC(true).argC(string("hello"));
00342     BOOST_CHECK_NO_THROW( mc.check() );
00343     shc = mc.send();
00344     shc.arg(cr);
00345     BOOST_CHECK( shc.ready() ); // 1 argument to collect.
00346     BOOST_CHECK_NO_THROW( shc.check() );
00347     // now collect:
00348     BOOST_CHECK_EQUAL( shc.collect(), SendSuccess);
00349     BOOST_CHECK_EQUAL( r, 0.0 );
00350     BOOST_CHECK_EQUAL( cr, -5.0 );
00351 
00352     
00353     mc = tp->provides("methods")->create("m0except", caller->engine());
00354     BOOST_CHECK_NO_THROW( mc.check() );
00355     shc = mc.send();
00356     BOOST_CHECK( shc.ready() ); // 1 argument to collect.
00357     BOOST_CHECK_NO_THROW( shc.check() );
00358     // now collect:
00359     BOOST_CHECK_THROW( shc.collect(), std::runtime_error);
00360     BOOST_REQUIRE( tc->inException() );
00361 }
00362 
00363 BOOST_AUTO_TEST_CASE( testRemoteOperationCallerCall )
00364 {
00365 
00366     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00367     tp = corba::TaskContextProxy::Create( ts->server(), true );
00368 
00369     // This test tests 'transparant' remote invocation of Orocos methods.
00370     // This requires the internal::RemoteOperationCaller class, which does not work yet.
00371     RTT::OperationCaller<double(void)> m0 = tp->provides("methods")->getOperation("m0");
00372     RTT::OperationCaller<double(int)> m1 = tp->provides("methods")->getOperation("m1");
00373     RTT::OperationCaller<double(int,double)> m2 = tp->provides("methods")->getOperation("m2");
00374     RTT::OperationCaller<double(int,double,bool)> m3 = tp->provides("methods")->getOperation("m3");
00375     RTT::OperationCaller<double(int,double,bool,std::string)> m4 = tp->provides("methods")->getOperation("m4");
00376     RTT::OperationCaller<void(void)> m0e = tp->provides("methods")->getOperation("m0except");
00377 
00378     BOOST_CHECK_EQUAL( -1.0, m0() );
00379     BOOST_CHECK_EQUAL( -2.0, m1(1) );
00380     BOOST_CHECK_EQUAL( -3.0, m2(1, 2.0) );
00381     BOOST_CHECK_EQUAL( -4.0, m3(1, 2.0, true) );
00382     BOOST_CHECK_EQUAL( -5.0, m4(1, 2.0, true,"hello") );
00383     BOOST_CHECK_THROW( m0e(), std::runtime_error );
00384     BOOST_REQUIRE( tc->inException() );
00385 }
00386 
00387 BOOST_AUTO_TEST_CASE( testAnyOperationCaller )
00388 {
00389     double d;
00390 
00391     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00392     tp = corba::TaskContextProxy::Create( ts->server() , true);
00393 
00394     // This test tests the callOperation() function of the server.
00395     corba::CService_var co = ts->server()->getProvider("methods");
00396     BOOST_CHECK( co.in() );
00397 
00398     corba::CAnyArguments_var any_args = new corba::CAnyArguments(0);
00399     CORBA::Any_var vm0 = co->callOperation("vm0", any_args.inout() );
00400     //BOOST_CHECK( vm0.in() );
00401 
00402     CORBA::Any_var m0 = co->callOperation("m0", any_args.inout());
00403     BOOST_CHECK( m0 >>= d );
00404     BOOST_CHECK_EQUAL(d, -1.0 );
00405 
00406     any_args = new corba::CAnyArguments(1);
00407     any_args->length(1);
00408     unsigned int index = 0;
00409     any_args[index] <<= (CORBA::Long) 1;
00410     CORBA::Any_var m1;
00411     BOOST_CHECK_NO_THROW( m1 = co->callOperation("m1", any_args.inout()));
00412     BOOST_CHECK( m1 >>= d );
00413     BOOST_CHECK_EQUAL(d, -2.0 );
00414 
00415     any_args = new corba::CAnyArguments(2);
00416     any_args->length(2);
00417     index = 0;
00418     any_args[index] <<= (CORBA::Long) 1;
00419     ++index;
00420     any_args[index] <<= (CORBA::Double) 2.0;
00421     CORBA::Any_var m2;
00422     BOOST_CHECK_NO_THROW( m2 = co->callOperation("m2", any_args.inout()));
00423     BOOST_CHECK( m2 >>= d );
00424     BOOST_CHECK_EQUAL(d, -3.0 );
00425 
00426     any_args = new corba::CAnyArguments(3);
00427     any_args->length(3);
00428      index = 0;
00429     any_args[index] <<= (CORBA::Long) 1;
00430     ++index;
00431     any_args[index] <<= (CORBA::Double) 2.0;
00432     ++index;
00433     any_args[index] <<= CORBA::Any::from_boolean( true );
00434     CORBA::Any_var m3;
00435     BOOST_CHECK_NO_THROW( m3= co->callOperation("m3", any_args.inout()) );
00436     BOOST_CHECK( m3 >>= d );
00437     BOOST_CHECK_EQUAL(d, -4.0 );
00438 
00439     any_args = new corba::CAnyArguments(4);
00440     any_args->length(4);
00441     index = 0;
00442     any_args[index] <<= (CORBA::Long) 1;
00443     ++index;
00444     any_args[index] <<= (CORBA::Double) 2.0;
00445     ++index;
00446     any_args[index] <<= CORBA::Any::from_boolean( true );
00447     ++index;
00448     any_args[index] <<= "hello";
00449     CORBA::Any_var m4;
00450     BOOST_CHECK_NO_THROW ( m4 = co->callOperation("m4", any_args.inout()) );
00451     BOOST_CHECK( m4 >>= d );
00452     BOOST_CHECK_EQUAL(d, -5.0 );
00453 
00454     any_args = new corba::CAnyArguments(0);
00455     BOOST_CHECK_THROW(co->callOperation("m0except", any_args.inout() ), ::RTT::corba::CCallError);
00456     BOOST_REQUIRE( tc->inException() );
00457 }
00458 
00459 BOOST_AUTO_TEST_CASE(testDataFlowInterface)
00460 {
00461     ts = corba::TaskContextServer::Create( tc, false ); //no-naming
00462 
00463     corba::CDataFlowInterface_var ports = ts->server()->ports();
00464 
00465     corba::CDataFlowInterface::CPortNames_var names =
00466         ports->getPorts();
00467 
00468     BOOST_CHECK_EQUAL(CORBA::ULong(2), names->length());
00469     BOOST_CHECK_EQUAL(string("mi"), string(names[CORBA::ULong(0)]));
00470     BOOST_CHECK_EQUAL(string("mo"), string(names[CORBA::ULong(1)]));
00471 
00472     // Now check directions
00473     BOOST_CHECK_EQUAL(RTT::corba::COutput,
00474             ports->getPortType("mo"));
00475     BOOST_CHECK_EQUAL(RTT::corba::CInput,
00476             ports->getPortType("mi"));
00477 
00478     // And check type names
00479         CORBA::String_var cstr = ports->getDataType("mo");
00480     BOOST_CHECK_EQUAL(string("double"),
00481             string(cstr.in()));
00482 }
00483 
00484 BOOST_AUTO_TEST_CASE( testPortConnections )
00485 {
00486     // This test tests the differen port-to-port connections.
00487     ts  = corba::TaskContextServer::Create( tc, false ); //no-naming
00488     ts2 = corba::TaskContextServer::Create( t2, false ); //no-naming
00489 
00490     // Create a default CORBA policy specification
00491     RTT::corba::CConnPolicy policy;
00492     policy.type = RTT::corba::CData;
00493     policy.init = false;
00494     policy.lock_policy = RTT::corba::CLockFree;
00495     policy.size = 0;
00496     policy.transport = ORO_CORBA_PROTOCOL_ID; // force creation of non-local connections
00497 
00498     corba::CDataFlowInterface_var ports  = ts->server()->ports();
00499     corba::CDataFlowInterface_var ports2 = ts2->server()->ports();
00500 
00501     // Test cases that should not connect
00502     BOOST_CHECK_THROW( ports->createConnection("mo", ports2, "does_not_exist", policy), CNoSuchPortException );
00503     BOOST_CHECK_THROW( ports->createConnection("does_not_exist", ports2, "mi", policy), CNoSuchPortException );
00504     BOOST_CHECK_THROW( ports->createConnection("does_not_exist", ports2, "does_not_exist", policy), CNoSuchPortException );
00505     BOOST_CHECK_THROW( ports->createConnection("mo", ports2, "mo", policy), CNoSuchPortException );
00506     BOOST_CHECK_THROW( ports->createConnection("mi", ports2, "mi", policy), CNoSuchPortException );
00507     BOOST_CHECK_THROW( ports->createConnection("mi", ports2, "mo", policy), CNoSuchPortException );
00508 
00509     // must be running to catch event port signalling.
00510     BOOST_CHECK( t2->start() );
00511     // WARNING: in the following, there is four configuration tested. There is
00512     // also three different ways to disconnect. We need to test those three
00513     // "disconnection methods", so beware when you change something ...
00514 
00515     policy.type = RTT::corba::CData;
00516     policy.pull = false;
00517     BOOST_CHECK( ports->createConnection("mo", ports2, "mi", policy) );
00518     testPortDataConnection();
00519     ports->disconnectPort("mo");
00520     testPortDisconnected();
00521 
00522     policy.type = RTT::corba::CData;
00523     policy.pull = true;
00524     BOOST_CHECK( ports->createConnection("mo", ports2, "mi", policy) );
00525     testPortDataConnection();
00526     ports2->disconnectPort("mi");
00527     testPortDisconnected();
00528 
00529     policy.type = RTT::corba::CBuffer;
00530     policy.pull = false;
00531     policy.size = 3;
00532     BOOST_CHECK( ports->createConnection("mo", ports2, "mi", policy) );
00533     testPortBufferConnection();
00534     ports->disconnectPort("mo");
00535     testPortDisconnected();
00536 
00537     policy.type = RTT::corba::CBuffer;
00538     policy.pull = true;
00539     BOOST_CHECK( ports->createConnection("mo", ports2, "mi", policy) );
00540     testPortBufferConnection();
00541     // Here, check removal of specific connections. So first add another
00542     // connection ...
00543     mo1->createConnection(*mi1);
00544     // Remove the remote connection
00545     ports->removeConnection("mo", ports2, "mi");
00546     // Check it is removed
00547     BOOST_CHECK(mo1->connected());
00548     BOOST_CHECK(mi1->connected());
00549     BOOST_CHECK(!mi2->connected());
00550 }
00551 
00552 BOOST_AUTO_TEST_CASE( testPortProxying )
00553 {
00554     ts  = corba::TaskContextServer::Create( tc, false ); //no-naming
00555     tp  = corba::TaskContextProxy::Create( ts->server(), true );
00556     ts2  = corba::TaskContextServer::Create( t2, false ); //no-naming
00557     tp2  = corba::TaskContextProxy::Create( ts2->server(), true );
00558 
00559     base::PortInterface* untyped_port;
00560 
00561     untyped_port = tp->ports()->getPort("mi");
00562     BOOST_CHECK(untyped_port);
00563     base::InputPortInterface* read_port = dynamic_cast<base::InputPortInterface*>(tp->ports()->getPort("mi"));
00564     BOOST_CHECK(read_port);
00565 
00566     untyped_port = tp->ports()->getPort("mi");
00567     BOOST_CHECK(untyped_port);
00568     base::OutputPortInterface* write_port = dynamic_cast<base::OutputPortInterface*>(tp2->ports()->getPort("mo"));
00569     BOOST_CHECK(write_port);
00570 
00571     // Just make sure 'read_port' and 'write_port' are actually proxies and not
00572     // the real thing
00573     BOOST_CHECK(dynamic_cast<corba::RemoteInputPort*>(read_port));
00574     BOOST_CHECK(dynamic_cast<corba::RemoteOutputPort*>(write_port));
00575 
00576     BOOST_CHECK(!read_port->connected());
00577     BOOST_CHECK(read_port->getTypeInfo() == mi1->getTypeInfo());
00578     BOOST_CHECK(!write_port->connected());
00579     BOOST_CHECK(write_port->getTypeInfo() == mo2->getTypeInfo());
00580 
00581     mo2->createConnection(*read_port);
00582     BOOST_CHECK(read_port->connected());
00583     BOOST_CHECK(write_port->connected());
00584     read_port->disconnect();
00585     BOOST_CHECK(!read_port->connected());
00586     BOOST_CHECK(!write_port->connected());
00587 
00588     mo2->createConnection(*read_port);
00589     BOOST_CHECK(read_port->connected());
00590     BOOST_CHECK(write_port->connected());
00591     write_port->disconnect();
00592     BOOST_CHECK(!read_port->connected());
00593     BOOST_CHECK(!write_port->connected());
00594 
00595     // Test cloning
00596     auto_ptr<base::InputPortInterface> read_clone(dynamic_cast<base::InputPortInterface*>(read_port->clone()));
00597     BOOST_CHECK(mo2->createConnection(*read_clone));
00598     BOOST_CHECK(read_clone->connected());
00599     BOOST_CHECK(!read_port->connected());
00600     mo2->disconnect();
00601 }
00602 
00603 BOOST_AUTO_TEST_CASE( testDataHalfs )
00604 {
00605     double result;
00606     // This test tests the differen port-to-port connections.
00607     ts  = corba::TaskContextServer::Create( tc, false ); //no-naming
00608 
00609     // Create a default CORBA policy specification
00610     RTT::corba::CConnPolicy policy;
00611     policy.type = RTT::corba::CData;
00612     policy.init = false;
00613     policy.lock_policy = RTT::corba::CLockFree;
00614     policy.size = 0;
00615     policy.transport = ORO_CORBA_PROTOCOL_ID; // force creation of non-local connections
00616 
00617     corba::CDataFlowInterface_var ports  = ts->server()->ports();
00618     BOOST_REQUIRE( ports.in() );
00619 
00620     // test unbuffered C++ write --> Corba read
00621     policy.pull = false; // note: buildChannelInput must correct policy to pull = true (adds a buffer).
00622     CChannelElement_var cce = ports->buildChannelInput("mo", policy);
00623     CORBA::Any_var sample = new CORBA::Any();
00624     BOOST_REQUIRE( cce.in() );
00625 
00626     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), CNoData );
00627     // Check read of new data
00628     mo1->write( 3.33 );
00629     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), CNewData );
00630     sample >>= result;
00631     BOOST_CHECK_EQUAL( result, 3.33);
00632 
00633     // Check re-read of old data.
00634     sample <<= 0.0;
00635     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), COldData );
00636     sample >>= result;
00637     BOOST_CHECK_EQUAL( result, 3.33);
00638 
00639     cce->disconnect();
00640 
00641     // test unbuffered Corba write --> C++ read
00642     cce = ports->buildChannelOutput("mi", policy);
00643     ports->channelReady("mi", cce);
00644     sample = new CORBA::Any();
00645     BOOST_REQUIRE( cce.in() );
00646 
00647     // Check read of new data
00648     result = 0.0;
00649     sample <<= 4.44;
00650     cce->write( sample.in() );
00651     BOOST_CHECK_EQUAL( mi1->read( result ), NewData );
00652     BOOST_CHECK_EQUAL( result, 4.44 );
00653 
00654     // Check re-read of old data.
00655     result = 0.0;
00656     BOOST_CHECK_EQUAL( mi1->read( result ), OldData );
00657     BOOST_CHECK_EQUAL( result, 4.44);
00658 }
00659 
00660 BOOST_AUTO_TEST_CASE( testBufferHalfs )
00661 {
00662     double result;
00663     // This test tests the differen port-to-port connections.
00664     ts  = corba::TaskContextServer::Create( tc, false ); //no-naming
00665 
00666     // Create a default CORBA policy specification
00667     RTT::corba::CConnPolicy policy;
00668     policy.type = RTT::corba::CBuffer;
00669     policy.init = false;
00670     policy.lock_policy = RTT::corba::CLockFree;
00671     policy.size = 10;
00672     policy.transport = ORO_CORBA_PROTOCOL_ID; // force creation of non-local connections
00673 
00674     corba::CDataFlowInterface_var ports  = ts->server()->ports();
00675     BOOST_REQUIRE( ports.in() );
00676 
00677     // test unbuffered C++ write --> Corba read
00678     policy.pull = false; // note: buildChannelInput must correct policy to pull = true (adds a buffer).
00679     CChannelElement_var cce = ports->buildChannelInput("mo", policy);
00680     CORBA::Any_var sample = new CORBA::Any();
00681     BOOST_REQUIRE( cce.in() );
00682 
00683     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), CNoData );
00684     // Check read of new data
00685     mo1->write( 6.33 );
00686     mo1->write( 3.33 );
00687     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), CNewData );
00688     sample >>= result;
00689     BOOST_CHECK_EQUAL( result, 6.33);
00690     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), CNewData );
00691     sample >>= result;
00692     BOOST_CHECK_EQUAL( result, 3.33);
00693 
00694     // Check re-read of old data.
00695     sample <<= 0.0;
00696     BOOST_CHECK_EQUAL( cce->read( sample.out(), true ), COldData );
00697     sample >>= result;
00698     BOOST_CHECK_EQUAL( result, 3.33);
00699 
00700     cce->disconnect();
00701 
00702     // test unbuffered Corba write --> C++ read
00703     cce = ports->buildChannelOutput("mi", policy);
00704     ports->channelReady("mi", cce);
00705     sample = new CORBA::Any();
00706     BOOST_REQUIRE( cce.in() );
00707 
00708     // Check read of new data
00709     result = 0.0;
00710     sample <<= 6.44;
00711     cce->write( sample.in() );
00712     sample <<= 4.44;
00713     cce->write( sample.in() );
00714     BOOST_CHECK_EQUAL( mi1->read( result ), NewData );
00715     BOOST_CHECK_EQUAL( result, 6.44 );
00716     BOOST_CHECK_EQUAL( mi1->read( result ), NewData );
00717     BOOST_CHECK_EQUAL( result, 4.44 );
00718 
00719     // Check re-read of old data.
00720     result = 0.0;
00721     BOOST_CHECK_EQUAL( mi1->read( result ), OldData );
00722     BOOST_CHECK_EQUAL( result, 4.44);
00723 }
00724 
00725 BOOST_AUTO_TEST_SUITE_END()
00726 


rtt
Author(s): RTT Developers
autogenerated on Thu Jan 2 2014 11:35:19