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
00039 #ifndef RTT_CORBA_REMOTE_PORTS_HPP
00040 #define RTT_CORBA_REMOTE_PORTS_HPP
00041
00042 #include "../../base/PortInterface.hpp"
00043 #include "../../base/ChannelElement.hpp"
00044 #include "../../InputPort.hpp"
00045 #include "../../OutputPort.hpp"
00046 #include "DataFlowI.h"
00047 #include <cassert>
00048
00049 namespace RTT {
00050 namespace corba {
00061 template<typename PortClass>
00062 class RemotePort : public PortClass
00063 {
00064 protected:
00065 types::TypeInfo const* type_info;
00066 CDataFlowInterface_var dataflow;
00067 PortableServer::POA_var mpoa;
00068
00069 bool connectionAdded( base::ChannelElementBase::shared_ptr channel, ConnPolicy const& policy ) { assert(false && "Can/Should not add connection to remote port object !");return false; }
00070
00071 public:
00072 RemotePort(types::TypeInfo const* type_info,
00073 CDataFlowInterface_ptr dataflow,
00074 std::string const& name,
00075 PortableServer::POA_ptr poa);
00076
00077 PortableServer::POA_ptr _default_POA();
00078 CDataFlowInterface_ptr getDataFlowInterface() const;
00079
00080 internal::ConnID* getPortID() const;
00081
00082 types::TypeInfo const* getTypeInfo() const;
00083 int serverProtocol() const;
00084 bool connected() const;
00085 bool createStream( const ConnPolicy& policy );
00086 virtual bool addConnection(internal::ConnID* port_id, base::ChannelElementBase::shared_ptr channel_input, ConnPolicy const& policy);
00087 void disconnect();
00088 bool disconnect(base::PortInterface* p);
00089 };
00090
00096 class RemoteOutputPort
00097 : public RemotePort<base::OutputPortInterface>
00098 {
00099 public:
00100 RemoteOutputPort(types::TypeInfo const* type_info,
00101 CDataFlowInterface_ptr dataflow,
00102 std::string const& name,
00103 PortableServer::POA_ptr poa);
00104
00105 bool keepsLastWrittenValue() const;
00106 void keepLastWrittenValue(bool new_flag);
00107
00108 using base::OutputPortInterface::createConnection;
00109 bool createConnection( base::InputPortInterface& sink, ConnPolicy const& policy );
00110
00111 virtual base::DataSourceBase::shared_ptr getDataSource() const;
00112
00113 base::PortInterface* clone() const;
00114 base::PortInterface* antiClone() const;
00115 };
00116
00123 class RemoteInputPort
00124 : public RemotePort<base::InputPortInterface>
00125 {
00126 typedef std::map<base::ChannelElementBase*,RTT::corba::CChannelElement_var> ChannelMap;
00127 ChannelMap channel_map;
00128 protected:
00136 virtual bool addConnection(internal::ConnID* port_id, base::ChannelElementBase::shared_ptr channel_input, ConnPolicy const& policy) { return true; }
00137 public:
00138 RemoteInputPort(types::TypeInfo const* type_info,
00139 CDataFlowInterface_ptr dataflow,
00140 std::string const& name,
00141 PortableServer::POA_ptr poa);
00142
00155 base::ChannelElementBase::shared_ptr buildRemoteChannelOutput(
00156 base::OutputPortInterface& output_port,
00157 types::TypeInfo const* type,
00158 base::InputPortInterface& reader_,
00159 ConnPolicy const& policy);
00160
00161 base::PortInterface* clone() const;
00162 base::PortInterface* antiClone() const;
00163
00164 base::DataSourceBase* getDataSource();
00165
00173 virtual bool channelReady(base::ChannelElementBase::shared_ptr channel, ConnPolicy const& policy);
00174 };
00175 }
00176 }
00177
00178 #endif
00179