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


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