Go to the documentation of this file.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 
00037 
00038 #include "TaskContextProxy.hpp"
00039 #include "TaskContextServer.hpp"
00040 #include "TaskContextC.h"
00041 #include "CorbaOperationCallerFactory.hpp"
00042 #include "CorbaLib.hpp"
00043 #include "OperationCallerProxy.hpp"
00044 
00045 #include "../../types/Types.hpp"
00046 #include "../../extras/SequentialActivity.hpp"
00047 #include "corba.h"
00048 #ifdef CORBA_IS_TAO
00049 #include "tao/TimeBaseC.h"
00050 #include "tao/Messaging/Messaging.h"
00051 #include "tao/Messaging/Messaging_RT_PolicyC.h"
00052 #include "orbsvcs/CosNamingC.h"
00053 #include <ace/String_Base.h>
00054 #else
00055 #include <omniORB4/Naming.hh>
00056 #endif
00057 #include <iostream>
00058 #include <fstream>
00059 #include <string>
00060 
00061 #include "RemotePorts.hpp"
00062 
00063 using namespace std;
00064 using namespace RTT::detail;
00065 
00066 namespace RTT
00067 {namespace corba
00068 {
00069     IllegalServer::IllegalServer() : reason("This server does not exist or has the wrong type.") {}
00070 
00071     IllegalServer::IllegalServer(const std::string& r) : reason(r) {}
00072 
00073     IllegalServer::~IllegalServer() throw() {}
00074 
00075     const char* IllegalServer::what() const throw() { return reason.c_str(); }
00076 
00077 
00078     std::map<TaskContextProxy*, corba::CTaskContext_ptr> TaskContextProxy::proxies;
00079 
00080     PortableServer::POA_var TaskContextProxy::proxy_poa;
00081 
00082     TaskContextProxy::~TaskContextProxy()
00083     {
00084         log(Info) << "Terminating TaskContextProxy for " <<  this->getName() <<endlog();
00085         if ( this->properties() ) {
00086             deletePropertyBag( *this->properties() );
00087         }
00088         this->attributes()->clear();
00089         for (list<PortInterface*>::iterator it = port_proxies.begin(); it != port_proxies.end(); ++it)
00090             delete *it;
00091         proxies.erase(this);
00092     }
00093 
00094     TaskContextProxy::TaskContextProxy(std::string name, bool is_ior)
00095         : TaskContext("NotFound")
00096     {
00097         Logger::In in("TaskContextProxy");
00098         this->clear();
00099         this->setActivity( new SequentialActivity() );
00100         try {
00101             if (is_ior) {
00102                 
00103                 
00104                 
00105                 CORBA::Object_var task_object =
00106                     orb->string_to_object ( name.c_str() );
00107 
00108                 
00109                 mtask = corba::CTaskContext::_narrow (task_object.in ());
00110             } else {
00111                 
00112                 CORBA::Object_var rootObj;
00113                 CosNaming::NamingContext_var rootContext;
00114                 try {
00115                     rootObj = orb->resolve_initial_references("NameService");
00116                     rootContext = CosNaming::NamingContext::_narrow(rootObj);
00117                 } catch (...) {}
00118 
00119                 if (CORBA::is_nil(rootContext)) {
00120                     std::string err("TaskContextProxy could not acquire NameService.");
00121                     log(Error) << err <<endlog();
00122                     throw IllegalServer(err);
00123                 }
00124                 Logger::log() <<Logger::Debug << "TaskContextProxy found CORBA NameService."<<endlog();
00125                 CosNaming::Name serverName;
00126                 serverName.length(2);
00127                 serverName[0].id = CORBA::string_dup("TaskContexts");
00128                 serverName[1].id = CORBA::string_dup( name.c_str() );
00129 
00130                 
00131                 CORBA::Object_var task_object = rootContext->resolve(serverName);
00132                 mtask = corba::CTaskContext::_narrow (task_object.in ());
00133             }
00134             if ( CORBA::is_nil( mtask ) ) {
00135                 std::string err("Failed to acquire TaskContextServer '"+name+"'.");
00136                 Logger::log() << Logger::Error << err <<endlog();
00137                 throw IllegalServer(err);
00138             }
00139             CORBA::String_var nm = mtask->getName(); 
00140             std::string newname( nm.in() );
00141             this->provides()->setName( newname );
00142             Logger::log() << Logger::Info << "Successfully connected to TaskContextServer '"+newname+"'."<<endlog();
00143             proxies[this] = mtask.in();
00144         }
00145         catch (CORBA::Exception &e) {
00146             log(Error)<< "CORBA exception raised when resolving Object !" << endlog();
00147             Logger::log() << CORBA_EXCEPTION_INFO(e) << endlog();
00148             throw;
00149         }
00150         catch (IllegalServer& e) {
00151             
00152             throw e;
00153         }
00154         catch (...) {
00155             log(Error) <<"Unknown Exception in TaskContextProxy construction!"<<endlog();
00156             throw;
00157         }
00158 
00159         this->synchronize();
00160     }
00161 
00162     TaskContextProxy::TaskContextProxy( ::RTT::corba::CTaskContext_ptr taskc)
00163         : TaskContext("CORBAProxy"), mtask( corba::CTaskContext::_duplicate(taskc) )
00164     {
00165         Logger::In in("TaskContextProxy");
00166         this->clear();
00167         
00168         this->forceActivity( new SequentialActivity );
00169         try {
00170             CORBA::String_var nm = mtask->getName(); 
00171             std::string name( nm.in() );
00172             this->provides()->setName( name );
00173             proxies[this] = mtask.in();
00174         }
00175         catch (CORBA::Exception &e) {
00176             log(Error) << "CORBA exception raised when creating TaskContextProxy!" << Logger::nl;
00177             Logger::log() << CORBA_EXCEPTION_INFO(e) << endlog();
00178         }
00179         catch (...) {
00180             throw;
00181         }
00182         this->synchronize();
00183     }
00184 
00185     void TaskContextProxy::synchronize()
00186     {
00187         
00188         
00189         if (CORBA::is_nil(mtask))
00190             return;
00191         
00192         CService_var serv = mtask->getProvider("this");
00193         this->fetchServices(this->provides(), serv.in() );
00194 
00195         CServiceRequester_var srq = mtask->getRequester("this");
00196         this->fetchRequesters(this->requires(), srq.in() );
00197         log(Debug) << "All Done."<<endlog();
00198     }
00199 
00200     void TaskContextProxy::fetchRequesters(ServiceRequester* parent, CServiceRequester_ptr csrq)
00201     {
00202         COperationCallerNames_var opcnames = csrq->getOperationCallerNames();
00203 
00204         log(Debug) << "Fetching OperationCallers of " << parent->getRequestName()<<endlog();
00205         for ( size_t i=0; i < opcnames->length(); ++i) {
00206             if ( parent->getOperationCaller( string(opcnames[i].in() )))
00207                 continue; 
00208             log(Debug) << "Requiring operation: "<< opcnames[i].in() <<endlog();
00209             parent->addOperationCaller( * new OperationCallerProxy(string(opcnames[i].in() ), CServiceRequester::_duplicate(csrq) ));
00210         }
00211 
00212         CRequestNames_var rqlist = csrq->getRequestNames();
00213 
00214         for( size_t i =0; i != rqlist->length(); ++i) {
00215             if ( string( rqlist[i] ) == "this")
00216                 continue;
00217             CServiceRequester_var cobj = csrq->getRequest(rqlist[i]);
00218 
00219             ServiceRequester* tobj = this->requires(std::string(rqlist[i]));
00220 
00221             
00222             this->fetchRequesters( tobj, cobj.in() );
00223         }
00224     }
00225 
00226     
00227     void TaskContextProxy::fetchServices(Service::shared_ptr parent, CService_ptr serv)
00228     {
00229         log(Debug) << "Fetching "<<parent->getName()<<" Service:"<<endlog();
00230 
00231         
00232         this->fetchPorts(parent, serv);
00233 
00234         
00235         
00236         log(Debug) << "Fetching Operations."<<endlog();
00237         COperationInterface::COperationList_var objs;
00238         objs = serv->getOperations();
00239         for ( size_t i=0; i < objs->length(); ++i) {
00240             if ( parent->hasMember( string(objs[i].in() )))
00241                 continue; 
00242             log(Debug) << "Providing operation: "<< objs[i].in() <<endlog();
00243             parent->add( objs[i].in(), new CorbaOperationCallerFactory( objs[i].in(), serv, ProxyPOA() ) );
00244         }
00245 
00246         
00247         log(Debug) << "Fetching Properties."<<endlog();
00248         
00249         CConfigurationInterface::CPropertyNames_var props = serv->getPropertyList();
00250 
00251         for (size_t i=0; i != props->length(); ++i) {
00252             if ( findProperty( *parent->properties(), string(props[i].name.in()), "." ) )
00253                 continue; 
00254             if ( !serv->hasProperty( props[i].name.in() ) ) {
00255                 log(Error) <<"Property "<< string(props[i].name.in()) << " present in getPropertyList() but not accessible."<<endlog();
00256                 continue;
00257             }
00258            
00259             CORBA::String_var tn = serv->getPropertyTypeName(props[i].name.in());
00260             TypeInfo* ti = TypeInfoRepository::Instance()->type( tn.in() );
00261 
00262             
00263             string pname = string( props[i].name.in() );
00264             pname = pname.substr( pname.rfind(".") + 1 );
00265             string prefix = string( props[i].name.in() );
00266             if ( prefix.rfind(".") == string::npos ) {
00267                 prefix.clear();
00268             }
00269             else {
00270                 prefix = prefix.substr( 0, prefix.rfind(".") );
00271             }
00272 
00273             if ( ti && ti->hasProtocol(ORO_CORBA_PROTOCOL_ID)) {
00274                 CorbaTypeTransporter* ctt = dynamic_cast<CorbaTypeTransporter*>(ti->getProtocol(ORO_CORBA_PROTOCOL_ID));
00275                 assert(ctt);
00276                 
00277                 DataSourceBase::shared_ptr ds = ctt->createPropertyDataSource( serv, props[i].name.in() );
00278                 storeProperty( *parent->properties(), prefix, ti->buildProperty( pname, props[i].description.in(), ds));
00279                 log(Debug) << "Looked up Property " << tn.in() << " "<< pname <<": created."<<endlog();
00280             }
00281             else {
00282                 if ( string("PropertyBag") == tn.in() ) {
00283                     storeProperty(*parent->properties(), prefix, new Property<PropertyBag>( pname, props[i].description.in()) );
00284                     log(Debug) << "Looked up PropertyBag " << tn.in() << " "<< pname <<": created."<<endlog();
00285                 } else
00286                     log(Error) << "Looked up Property " << tn.in() << " "<< pname <<": type not known. Check your RTT_COMPONENT_PATH ( \""<<getenv("RTT_COMPONENT_PATH")<<" \")."<<endlog();
00287             }
00288         }
00289 
00290         log(Debug) << "Fetching Attributes."<<endlog();
00291         CConfigurationInterface::CAttributeNames_var attrs = serv->getAttributeList();
00292         for (size_t i=0; i != attrs->length(); ++i) {
00293             if ( parent->hasAttribute( string(attrs[i].in()) ) )
00294                 continue; 
00295             if ( !serv->hasAttribute( attrs[i].in() ) ) {
00296                 log(Error) <<"Attribute '"<< string(attrs[i].in()) << "' present in getAttributeList() but not accessible."<<endlog();
00297                 continue;
00298             }
00299             
00300             CORBA::String_var tn = serv->getAttributeTypeName( attrs[i].in() );
00301             TypeInfo* ti = TypeInfoRepository::Instance()->type( tn.in() );
00302             if ( ti && ti->hasProtocol(ORO_CORBA_PROTOCOL_ID) ) {
00303                 log(Debug) << "Looking up Attribute " << tn.in() <<": found!"<<endlog();
00304                 CorbaTypeTransporter* ctt = dynamic_cast<CorbaTypeTransporter*>(ti->getProtocol(ORO_CORBA_PROTOCOL_ID));
00305                 assert(ctt);
00306                 
00307                 DataSourceBase::shared_ptr ds = ctt->createAttributeDataSource( serv, attrs[i].in() );
00308                 if ( serv->isAttributeAssignable( attrs[i].in() ) )
00309                     parent->setValue( ti->buildAttribute( attrs[i].in(), ds));
00310                 else
00311                     parent->setValue( ti->buildConstant( attrs[i].in(), ds));
00312             } else {
00313                 log(Error) << "Looking up Attribute " << tn.in();
00314                 Logger::log() <<": type not known. Check your RTT_COMPONENT_PATH ( \""<<getenv("RTT_COMPONENT_PATH")<<" \")."<<endlog();
00315             }
00316         }
00317 
00318         CService::CProviderNames_var plist = serv->getProviderNames();
00319 
00320         for( size_t i =0; i != plist->length(); ++i) {
00321             if ( string( plist[i] ) == "this")
00322                 continue;
00323             CService_var cobj = serv->getService(plist[i]);
00324             CORBA::String_var descr = cobj->getServiceDescription();
00325 
00326             Service::shared_ptr tobj = parent->provides(std::string(plist[i]));
00327             tobj->doc( descr.in() );
00328 
00329             
00330             this->fetchServices( tobj, cobj.in() );
00331         }
00332     }
00333 
00334     
00335     void TaskContextProxy::fetchPorts(RTT::Service::shared_ptr parent, CDataFlowInterface_ptr dfact)
00336     {
00337         log(Debug) << "Fetching Ports for service "<<parent->getName()<<"."<<endlog();
00338         TypeInfoRepository::shared_ptr type_repo = TypeInfoRepository::Instance();
00339         if (dfact) {
00340             CDataFlowInterface::CPortDescriptions_var objs = dfact->getPortDescriptions();
00341             for ( size_t i=0; i < objs->length(); ++i) {
00342                 CPortDescription port = objs[i];
00343                 if (parent->getPort( port.name.in() ))
00344                     continue; 
00345 
00346                 TypeInfo const* type_info = type_repo->type(port.type_name.in());
00347                 if (!type_info)
00348                 {
00349                     log(Warning) << "remote port " << port.name
00350                         << " has a type that cannot be marshalled over CORBA: " << port.type_name << ". "
00351                         << "It is ignored by TaskContextProxy" << endlog();
00352                 }
00353                 else
00354                 {
00355                     PortInterface* new_port;
00356                     if (port.type == RTT::corba::CInput)
00357                         new_port = new RemoteInputPort( type_info, dfact, port.name.in(), ProxyPOA() );
00358                     else
00359                         new_port = new RemoteOutputPort( type_info, dfact, port.name.in(), ProxyPOA() );
00360 
00361                     parent->addPort(*new_port);
00362                     port_proxies.push_back(new_port); 
00363                 }
00364             }
00365         }
00366     }
00367 
00368     void TaskContextProxy::DestroyOrb()
00369     {
00370         try {
00371             
00372             
00373                 if (orb) {
00374                         orb->destroy();
00375                         rootPOA = 0;
00376                         orb = 0;
00377                         std::cerr <<"Orb destroyed."<<std::endl;
00378                 }
00379         }
00380         catch (CORBA::Exception &e) {
00381             log(Error) << "Orb Init : CORBA exception raised!" << Logger::nl;
00382             Logger::log() << CORBA_EXCEPTION_INFO(e) << endlog();
00383         }
00384     }
00385 
00386     TaskContextProxy* TaskContextProxy::Create(std::string name, bool is_ior ) {
00387         if ( CORBA::is_nil(orb) ) {
00388             log(Error) << "Won't create a proxy for '"<<name<<"' : orb is nill. Call TaskContextProxy::InitOrb(argc, argv); before TaskContextProxy::Create()." <<endlog();
00389             return 0;
00390         }
00391         if ( name.empty() ) {
00392             log(Error) << "Can't create a proxy with an empty name." <<endlog();
00393             return 0;
00394         }
00395         
00396         try {
00397             TaskContextProxy* ctp = new TaskContextProxy( name, is_ior );
00398             return ctp;
00399         }
00400         catch( IllegalServer& is ) {
00401             cerr << is.what() << endl;
00402         }
00403         return 0;
00404     }
00405 
00406     TaskContextProxy* TaskContextProxy::CreateFromFile(std::string name) {
00407         if ( CORBA::is_nil(orb) ) {
00408             log(Error) << "Won't create a proxy for '"<<name<<"' : orb is nill. Call TaskContextProxy::InitOrb(argc, argv); before TaskContextProxy::Create()." <<endlog();
00409             return 0;
00410         }
00411         if ( name.empty() ) {
00412             log(Error) << "Can't create a proxy with an empty file name." <<endlog();
00413             return 0;
00414         }
00415 
00416         
00417         ifstream namestream( name.c_str() );
00418         string ior;
00419         namestream >> ior;
00420         return Create( ior, true);
00421     }
00422 
00423     TaskContext* TaskContextProxy::Create(::RTT::corba::CTaskContext_ptr t, bool force_remote) {
00424         Logger::In in("TaskContextProxy::Create");
00425         if ( CORBA::is_nil(orb) ) {
00426             log(Error) << "Can not create proxy when ORB is nill !"<<endlog();
00427             return 0;
00428         }
00429         if ( CORBA::is_nil(t) ) {
00430             log(Error) << "Can not create proxy for nill peer !" <<endlog();
00431             return 0;
00432         }
00433 
00434         
00435         
00436         for (PMap::iterator it = proxies.begin(); it != proxies.end(); ++it)
00437             if ( (it->second)->_is_equivalent( t ) ) {
00438                 log(Debug) << "Existing proxy found !" <<endlog();
00439                 return it->first;
00440             }
00441 
00442         
00443         if (! force_remote)
00444         {
00445             for (TaskContextServer::ServerMap::iterator it = TaskContextServer::servers.begin(); it != TaskContextServer::servers.end(); ++it)
00446                 if ( it->second->server()->_is_equivalent( t ) ) {
00447                     log(Debug) << "Local server found !" <<endlog();
00448                     return it->first;
00449                 }
00450         }
00451 
00452         log(Debug) << "No local taskcontext found..." <<endlog();
00453         
00454         try {
00455             TaskContextProxy* ctp = new TaskContextProxy( t );
00456             return ctp;
00457         }
00458         catch( IllegalServer& is ) {
00459             cerr << is.what() << endl;
00460         }
00461         return 0;
00462     }
00463 
00464     bool TaskContextProxy::start() {
00465         try {
00466             if (! CORBA::is_nil(mtask) )
00467                 return mtask->start();
00468         } catch(...) {
00469             mtask = CTaskContext::_nil();
00470             this->setName("NotFound");
00471             this->clear();
00472         }
00473         return false;
00474     }
00475 
00476     bool TaskContextProxy::stop() {
00477         try {
00478             if (! CORBA::is_nil(mtask) )
00479                 return mtask->stop();
00480         } catch(...) {
00481             mtask = CTaskContext::_nil();
00482             this->setName("NotFound");
00483             this->clear();
00484         }
00485         return false;
00486     }
00487 
00488     bool TaskContextProxy::activate() {
00489         try {
00490             if (! CORBA::is_nil(mtask) )
00491                 return mtask->activate();
00492         } catch(...) {
00493             mtask = CTaskContext::_nil();
00494             this->setName("NotFound");
00495             this->clear();
00496         }
00497         return false;
00498     }
00499 
00500     bool TaskContextProxy::isActive() const {
00501         try {
00502             if (! CORBA::is_nil(mtask) )
00503                 return mtask->isActive();
00504         } catch(...) {
00505             mtask = CTaskContext::_nil();
00506         }
00507         return false;
00508     }
00509 
00510     bool TaskContextProxy::isRunning() const {
00511         try {
00512             if (! CORBA::is_nil(mtask) )
00513                 return mtask->isRunning();
00514         } catch(...) {
00515             mtask = CTaskContext::_nil();
00516         }
00517         return false;
00518     }
00519 
00520     bool TaskContextProxy::configure() {
00521         try {
00522             if (! CORBA::is_nil(mtask) )
00523                 return mtask->configure();
00524         } catch(...) {
00525             mtask = CTaskContext::_nil();
00526             this->setName("NotFound");
00527             this->clear();
00528         }
00529         return false;
00530     }
00531 
00532     bool TaskContextProxy::cleanup() {
00533         try {
00534             if (! CORBA::is_nil(mtask) )
00535                 return mtask->cleanup();
00536         } catch(...) {
00537             mtask = CTaskContext::_nil();
00538             this->setName("NotFound");
00539             this->clear();
00540         }
00541         return false;
00542     }
00543 
00544     bool TaskContextProxy::isConfigured() const {
00545         try {
00546             if (! CORBA::is_nil(mtask) )
00547                 return mtask->isConfigured();
00548         } catch(...) {
00549             mtask = CTaskContext::_nil();
00550         }
00551         return false;
00552     }
00553 
00554     bool TaskContextProxy::inFatalError() const {
00555         try {
00556             if (! CORBA::is_nil(mtask) )
00557                 return mtask->inFatalError();
00558         } catch(...) {
00559             mtask = CTaskContext::_nil();
00560         }
00561         return false;
00562     }
00563 
00564     bool TaskContextProxy::inRunTimeError() const {
00565         try {
00566             if (! CORBA::is_nil(mtask) )
00567                 return mtask->inRunTimeError();
00568         } catch(...) {
00569             mtask = CTaskContext::_nil();
00570         }
00571         return false;
00572     }
00573 
00574     TaskContext::TaskState TaskContextProxy::getTaskState() const {
00575         try {
00576             if (! CORBA::is_nil(mtask) )
00577                 return TaskContext::TaskState( mtask->getTaskState() );
00578         } catch(...) {
00579             mtask = CTaskContext::_nil();
00580         }
00581         return TaskContext::Init;
00582     }
00583 
00584     void TaskContextProxy::setName(const std::string& n)
00585     {
00586         
00587     }
00588 
00589     bool TaskContextProxy::addPeer( TaskContext* peer, std::string alias  )
00590     {
00591         try {
00592             if (CORBA::is_nil(mtask))
00593                 return false;
00594 
00595             
00596             TaskContextProxy* ctp = dynamic_cast<TaskContextProxy*>( peer );
00597             if (ctp) {
00598                 if ( mtask->addPeer( ctp->server(), alias.c_str() ) ) {
00599                     this->synchronize();
00600                     return true;
00601                 }
00602                 return false;
00603             }
00604             
00605             TaskContextServer* newpeer = TaskContextServer::Create(peer);
00606             if ( mtask->addPeer( newpeer->server(), alias.c_str() ) ) {
00607                 this->synchronize();
00608                 return true;
00609             }
00610         } catch(...) {
00611             mtask = CTaskContext::_nil();
00612             this->setName("NotFound");
00613             this->clear();
00614         }
00615         return false;
00616     }
00617 
00618     void TaskContextProxy::removePeer( const std::string& name )
00619     {
00620         try {
00621             if (CORBA::is_nil(mtask))
00622                 return;
00623             mtask->removePeer( name.c_str() );
00624         } catch(...) {
00625             mtask = CTaskContext::_nil();
00626             this->setName("NotFound");
00627             this->clear();
00628         }
00629     }
00630 
00631     void TaskContextProxy::removePeer( TaskContext* peer )
00632     {
00633         try {
00634             if (CORBA::is_nil(mtask))
00635                 return;
00636             mtask->removePeer( peer->getName().c_str() );
00637         } catch(...) {
00638             mtask = CTaskContext::_nil();
00639             this->setName("NotFound");
00640             this->clear();
00641         }
00642     }
00643 
00644     bool TaskContextProxy::connectPeers( TaskContext* peer )
00645     {
00646         try {
00647             if (CORBA::is_nil(mtask))
00648                 return false;
00649             TaskContextServer* newpeer = TaskContextServer::Create(peer);
00650             return mtask->connectPeers( newpeer->server() );
00651         } catch(...) {
00652             mtask = CTaskContext::_nil();
00653             this->setName("NotFound");
00654             this->clear();
00655         }
00656         return false;
00657     }
00658 
00659     void TaskContextProxy::disconnectPeers( const std::string& name )
00660     {
00661         try {
00662             if (! CORBA::is_nil(mtask) )
00663                 mtask->disconnectPeers( name.c_str() );
00664         } catch(...) {
00665             mtask = CTaskContext::_nil();
00666             this->setName("NotFound");
00667             this->clear();
00668         }
00669     }
00670 
00671     TaskContext::PeerList TaskContextProxy::getPeerList() const
00672     {
00673 
00674         TaskContext::PeerList vlist;
00675         try {
00676             if (! CORBA::is_nil(mtask) ) {
00677                 corba::CTaskContext::CPeerNames_var plist = mtask->getPeerList();
00678                 for( size_t i =0; i != plist->length(); ++i)
00679                     vlist.push_back( std::string( plist[i] ) );
00680             }
00681         } catch(...) {
00682             mtask = CTaskContext::_nil();
00683         }
00684         return vlist;
00685     }
00686 
00687     bool TaskContextProxy::hasPeer( const std::string& peer_name ) const
00688     {
00689         try {
00690             if (! CORBA::is_nil(mtask))
00691                 return mtask->hasPeer( peer_name.c_str() );
00692         } catch(...) {
00693             mtask = CTaskContext::_nil();
00694         }
00695         return false;
00696     }
00697 
00698     TaskContext* TaskContextProxy::getPeer(const std::string& peer_name ) const
00699     {
00700         try {
00701             if (CORBA::is_nil(mtask))
00702                 return 0;
00703             corba::CTaskContext_ptr ct = mtask->getPeer( peer_name.c_str() );
00704             if ( CORBA::is_nil(ct) )
00705                 return 0;
00706             return TaskContextProxy::Create( ct );
00707         } catch(...) {
00708             mtask = CTaskContext::_nil();
00709         }
00710         return 0;
00711     }
00712 
00713     bool TaskContextProxy::connectPorts( TaskContext* peer )
00714     {
00715         try {
00716             if (CORBA::is_nil(mtask))
00717                 return false;
00718             TaskContextServer* newpeer = TaskContextServer::Create(peer);
00719             return mtask->connectPorts( newpeer->server() );
00720         } catch(...) {
00721             mtask = CTaskContext::_nil();
00722             this->setName("NotFound");
00723             this->clear();
00724         }
00725         return false;
00726     }
00727 
00728     bool TaskContextProxy::connectServices( TaskContext* peer )
00729     {
00730         try {
00731             if (CORBA::is_nil(mtask))
00732                 return false;
00733             TaskContextServer* newpeer = TaskContextServer::Create(peer);
00734             return mtask->connectServices( newpeer->server() );
00735         } catch(...) {
00736             mtask = CTaskContext::_nil();
00737             this->setName("NotFound");
00738             this->clear();
00739         }
00740         return false;
00741     }
00742 
00743     bool TaskContextProxy::ready()
00744     {
00745         if (CORBA::is_nil(mtask)) {
00746             this->clear();
00747             return false;
00748         }
00749         try {
00750             mtask->getName(); 
00751             return true;
00752         } catch(...) {
00753             
00754             this->clear();
00755             mtask = CTaskContext::_nil();
00756         }
00757         return false;
00758     }
00759 
00760     corba::CTaskContext_ptr TaskContextProxy::server() const {
00761         if ( CORBA::is_nil(mtask) )
00762             return CTaskContext::_nil();
00763         return mtask.in();
00764     }
00765 
00766     PortableServer::POA_ptr TaskContextProxy::ProxyPOA() {
00767         if ( CORBA::is_nil(orb) )
00768             return PortableServer::POA::_nil();
00769         if ( CORBA::is_nil(proxy_poa) ) {
00770             CORBA::Object_var poa_object =
00771                 orb->resolve_initial_references ("RootPOA");
00772 
00773             
00774             
00775             
00776             
00777             
00778             proxy_poa =
00779                 PortableServer::POA::_narrow (poa_object.in ());
00780         }
00781         
00782         return proxy_poa.in();
00783     }
00784 }}
00785