OutPortPullConnectorTests.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
22 #ifndef OutPortPullConnector_cpp
23 #define OutPortPullConnector_cpp
24 
25 #include <cppunit/ui/text/TestRunner.h>
26 #include <cppunit/TextOutputter.h>
27 #include <cppunit/extensions/TestFactoryRegistry.h>
28 #include <cppunit/extensions/HelperMacros.h>
29 #include <cppunit/TestAssert.h>
30 
31 #include <coil/Properties.h>
32 
33 #include <rtm/idl/BasicDataTypeSkel.h>
34 #include <rtm/idl/DataPortSkel.h>
35 #include <rtm/Typename.h>
37 #include <rtm/CdrBufferBase.h>
38 #include <rtm/CORBA_SeqUtil.h>
39 #include <rtm/NVUtil.h>
40 #include <rtm/ConnectorBase.h>
41 #include <rtm/DataPortStatus.h>
42 #include <rtm/InPortBase.h>
43 #include <rtm/InPortConsumer.h>
44 #include <rtm/OutPortBase.h>
45 #include <rtm/PortAdmin.h>
46 #include <rtm/CorbaConsumer.h>
47 #include <rtm/PublisherBase.h>
48 
54 {
55 
57  : public RTC::ConnectorDataListenerT<RTC::TimedLong>
58  {
59  public:
60  DataListener(const char* name) : m_name(name) {}
61  virtual ~DataListener()
62  {
63  //std::cout << "dtor of " << m_name << std::endl;
64  }
65 
66  virtual void operator()(const RTC::ConnectorInfo& info,
67  const RTC::TimedLong& data)
68  {
69  //std::cout << "------------------------------" << std::endl;
70  //std::cout << "Data Listener: " << m_name << std::endl;
71  //std::cout << "Profile::name: " << info.name << std::endl;
72  //std::cout << "------------------------------" << std::endl;
73  };
74  std::string m_name;
75  };
76 
77 
79  : public RTC::ConnectorListener
80  {
81  public:
82  ConnListener(const char* name) : m_name(name) {}
83  virtual ~ConnListener()
84  {
85  //std::cout << "dtor of " << m_name << std::endl;
86  }
87 
88  virtual void operator()(const RTC::ConnectorInfo& info)
89  {
90  std::cout << "------------------------------" << std::endl;
91  std::cout << "Connector Listener: " << m_name << std::endl;
92  std::cout << "Profile::name: " << info.name << std::endl;
93  std::cout << "------------------------------" << std::endl;
94  };
95  std::string m_name;
96  };
97 
103  class Logger
104  {
105  public:
106  void log(const std::string& msg)
107  {
108  m_log.push_back(msg);
109  }
110 
111  int countLog(const std::string& msg)
112  {
113  int count = 0;
114  for (int i = 0; i < (int) m_log.size(); ++i)
115  {
116  if (m_log[i] == msg) ++count;
117  }
118  return count;
119  }
120 
121  private:
122  std::vector<std::string> m_log;
123  };
124 
130  template <class DataType>
132  : public RTC::BufferBase<DataType>
133  {
134  public:
136  RingBufferMock(long int length = 8)
137  {
138  m_logger = NULL;
139  logger.log("RingBufferMock::Constructor");
140  m_read_return_value = BUFFER_OK;
141  }
142  virtual ~RingBufferMock(void)
143  {
144  }
145 
146 
152  {
153  m_read_return_value = value;
154  }
159  virtual void init(const coil::Properties& prop)
160  {
161  }
166  virtual size_t length(void) const
167  {
168  return 0;
169  }
174  virtual ReturnCode length(size_t n)
175  {
176  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
177  }
182  virtual ReturnCode reset()
183  {
184  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
185  }
190  virtual DataType* wptr(long int n = 0)
191  {
192  return &m_data;
193  }
198  virtual ReturnCode advanceWptr(long int n = 1)
199  {
200  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
201  }
206  virtual ReturnCode put(const DataType& value)
207  {
208  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
209  }
214  virtual ReturnCode write(const DataType& value,
215  long int sec = -1, long int nsec = -1)
216  {
217  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
218  }
223  virtual size_t writable() const
224  {
225  return 0;
226  }
231  virtual bool full(void) const
232  {
233  return true;
234  }
239  virtual DataType* rptr(long int n = 0)
240  {
241  return &m_data;
242  }
247  virtual ReturnCode advanceRptr(long int n = 1)
248  {
249  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
250  }
255  virtual ReturnCode get(DataType& value)
256  {
257  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
258  }
263  virtual DataType& get()
264  {
265  return m_data;
266  }
271  virtual ReturnCode read(DataType& value,
272  long int sec = -1, long int nsec = -1)
273  {
274  if (m_logger != NULL)
275  {
276  m_logger->log("RingBufferMock::read");
277  }
278  logger.log("RingBufferMock::read");
279  return m_read_return_value; //BUFFER_OK;
280  }
285  virtual size_t readable() const
286  {
287  return 0;
288  }
293  virtual bool empty(void) const
294  {
295  return true;
296  }
302  {
303  m_logger = logger;
304  }
305 
306  static Logger logger;
307  private:
308  DataType m_data;
309  std::vector<DataType> m_buffer;
312  };
313 
314  template <class DataType>
317 
324  : public RTC::OutPortProvider,
325  public virtual ::POA_OpenRTM::OutPortCdr,
326  public virtual PortableServer::RefCountServantBase
327  {
328 
329  public:
331  {
332  m_logger = NULL;
333  }
335  {
336  }
342  {
343  if (m_logger != NULL)
344  {
345  m_logger->log("OutPortCorbaCdrProviderMock::init");
346  }
347  }
352  virtual ::OpenRTM::PortStatus get(::OpenRTM::CdrData_out data)
353  {
354  return ::OpenRTM::PORT_OK;
355  }
360  RTC::InPortConsumer::ReturnCode put(const cdrMemoryStream& data)
361  {
362  return PORT_OK;
363  }
369  {
370  return;
371  }
372 
377  bool subscribeInterface(const SDOPackage::NVList& properties)
378  {
379 
380  return true;;
381  }
382 
387  void unsubscribeInterface(const SDOPackage::NVList& properties)
388  {
389  }
390 
391 
397  {
398  m_logger = logger;
399  }
400 
402  {
403  }
404 
406  {
407  }
409  {
410  }
411 
412  private:
414 
415  };
416 
418  : public CppUnit::TestFixture
419  {
420  CPPUNIT_TEST_SUITE(OutPortPullConnectorTests);
421 
422  CPPUNIT_TEST(test_OutPortPullConnector);
423  CPPUNIT_TEST(test_write);
424  CPPUNIT_TEST(test_disconnect_getBuffer);
425  CPPUNIT_TEST(test_activate_deactivate);
426 
427  CPPUNIT_TEST_SUITE_END();
428 
429  private:
430  CORBA::ORB_ptr m_pORB;
431  PortableServer::POA_ptr m_pPOA;
432 
433 
434  public:
436 
441  {
442 
443  int argc(0);
444  char** argv(NULL);
445  m_pORB = CORBA::ORB_init(argc, argv);
446  m_pPOA = PortableServer::POA::_narrow(
447  m_pORB->resolve_initial_references("RootPOA"));
448  m_pPOA->the_POAManager()->activate();
449 
450  }
451 
456  {
457  }
458 
462  virtual void setUp()
463  {
464  //ConnectorDataListeners
466  new DataListener("ON_BUFFER_WRITE"), true);
468  new DataListener("ON_BUFFER_FULL"), true);
470  new DataListener("ON_BUFFER_WRITE_TIMEOUT"), true);
472  new DataListener("ON_BUFFER_OVERWRITE"), true);
474  new DataListener("ON_BUFFER_READ"), true);
476  new DataListener("ON_SEND"), true);
478  new DataListener("ON_RECEIVED"), true);
480  new DataListener("ON_RECEIVER_FULL"), true);
482  new DataListener("ON_RECEIVER_TIMEOUT"), true);
484  new DataListener("ON_RECEIVER_ERROR"), true);
485 
486  //ConnectorListeners
488  new ConnListener("ON_BUFFER_EMPTY"), true);
490  new ConnListener("ON_BUFFER_READ_TIMEOUT"), true);
492  new ConnListener("ON_SENDER_EMPTY"), true);
494  new ConnListener("ON_SENDER_TIMEOUT"), true);
496  new ConnListener("ON_SENDER_ERROR"), true);
498  new ConnListener("ON_CONNECT"), true);
500  new ConnListener("ON_DISCONNECT"), true);
501  }
502 
506  virtual void tearDown()
507  {
508  }
509 
515  {
516  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
517 
518  RTC::ConnectorProfile prof;
519  CORBA_SeqUtil::push_back(prof.properties,
520  NVUtil::newNV("dataport.interface_type",
521  "corba_cdr"));
522  CORBA_SeqUtil::push_back(prof.properties,
523  NVUtil::newNV("dataport.dataflow_type",
524  "push"));
525  CORBA_SeqUtil::push_back(prof.properties,
526  NVUtil::newNV("dataport.subscription_type",
527  "new"));
529  {
530  coil::Properties conn_prop;
531  NVUtil::copyToProperties(conn_prop, prof.properties);
532  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
533  }
535  Logger logger;
536  provider->setLogger(&logger);
537  RTC::ConnectorInfo profile_new(prof.name,
538  prof.connector_id,
539  CORBA_SeqUtil::refToVstring(prof.ports),
540  prop);
541  RTC::OutPortConnector* connector(0);
542  connector = new RTC::OutPortPullConnector(profile_new, provider, m_listeners, pbuffer);
543 
544  delete connector;
545 
546  //subscription_type
547  //Flush
548  CORBA_SeqUtil::push_back(prof.properties,
549  NVUtil::newNV("dataport.subscription_type",
550  ""));
551  {
552  coil::Properties conn_prop;
553  NVUtil::copyToProperties(conn_prop, prof.properties);
554  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
555  }
556  RTC::ConnectorInfo profile_flush(prof.name,
557  prof.connector_id,
558  CORBA_SeqUtil::refToVstring(prof.ports),
559  prop);
560  connector = new RTC::OutPortPullConnector(profile_flush, provider, m_listeners, 0);
561 
562  delete connector;
563  delete provider;
564  delete pbuffer;
565  }
566 
571  void test_write()
572  {
573  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
574  RTC::ConnectorProfile prof;
575  CORBA_SeqUtil::push_back(prof.properties,
576  NVUtil::newNV("dataport.interface_type",
577  "corba_cdr"));
578  CORBA_SeqUtil::push_back(prof.properties,
579  NVUtil::newNV("dataport.dataflow_type",
580  "push"));
581  CORBA_SeqUtil::push_back(prof.properties,
582  NVUtil::newNV("dataport.subscription_type",
583  "new"));
585  {
586  coil::Properties conn_prop;
587  NVUtil::copyToProperties(conn_prop, prof.properties);
588  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
589  }
591  Logger logger;
592  provider->setLogger(&logger);
593  RTC::ConnectorInfo profile_new(prof.name,
594  prof.connector_id,
595  CORBA_SeqUtil::refToVstring(prof.ports),
596  prop);
597  RTC::OutPortConnector* connector(0);
598  connector = new RTC::OutPortPullConnector(profile_new, provider, m_listeners, pbuffer);
599  cdrMemoryStream cdr;
600  RTC::TimedLong td;
601  td.data = 12345;
602  td >>= cdr;
603 
605  ret = connector->write(cdr);
606  CPPUNIT_ASSERT_EQUAL(RTC::DataPortStatus::PORT_OK, ret);
607 
608  delete connector;
609  delete provider;
610  delete pbuffer;
611 
612  }
613 
619  {
620  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
621  RTC::ConnectorProfile prof;
622  CORBA_SeqUtil::push_back(prof.properties,
623  NVUtil::newNV("dataport.interface_type",
624  "corba_cdr"));
625  CORBA_SeqUtil::push_back(prof.properties,
626  NVUtil::newNV("dataport.dataflow_type",
627  "push"));
628  CORBA_SeqUtil::push_back(prof.properties,
629  NVUtil::newNV("dataport.subscription_type",
630  "new"));
632  {
633  coil::Properties conn_prop;
634  NVUtil::copyToProperties(conn_prop, prof.properties);
635  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
636  }
638  Logger logger;
639  provider->setLogger(&logger);
640  RTC::ConnectorInfo profile_new(prof.name,
641  prof.connector_id,
642  CORBA_SeqUtil::refToVstring(prof.ports),
643  prop);
644  RTC::OutPortConnector* connector(0);
645  connector = new RTC::OutPortPullConnector(profile_new, provider, m_listeners, pbuffer);
646  CPPUNIT_ASSERT(pbuffer == connector->getBuffer());
647 
649  ret = connector->disconnect();
650  CPPUNIT_ASSERT_EQUAL(RTC::DataPortStatus::PORT_OK, ret);
651 
652  delete connector;
653  delete provider;
654  delete pbuffer;
655  }
656 
662  {
663  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
664  RTC::ConnectorProfile prof;
665  CORBA_SeqUtil::push_back(prof.properties,
666  NVUtil::newNV("dataport.interface_type",
667  "corba_cdr"));
668  CORBA_SeqUtil::push_back(prof.properties,
669  NVUtil::newNV("dataport.dataflow_type",
670  "push"));
671  CORBA_SeqUtil::push_back(prof.properties,
672  NVUtil::newNV("dataport.subscription_type",
673  "new"));
675  {
676  coil::Properties conn_prop;
677  NVUtil::copyToProperties(conn_prop, prof.properties);
678  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
679  }
681  Logger logger;
682  provider->setLogger(&logger);
683  RTC::ConnectorInfo profile_new(prof.name,
684  prof.connector_id,
685  CORBA_SeqUtil::refToVstring(prof.ports),
686  prop);
687  RTC::OutPortConnector* connector(0);
688  connector = new RTC::OutPortPullConnector(profile_new, provider, m_listeners, pbuffer);
689  connector->activate();
690  delete connector;
691 
692  connector = new RTC::OutPortPullConnector(profile_new, provider, m_listeners, pbuffer);
693 
694  delete connector;
695  delete provider;
696  delete pbuffer;
697  }
698  };
699 }; // namespace OutPortPullConnector
700 
701 /*
702  * Register test suite
703  */
705 
706 #ifdef LOCAL_MAIN
707 int main(int argc, char* argv[])
708 {
709 
710  FORMAT format = TEXT_OUT;
711  int target = 0;
712  std::string xsl;
713  std::string ns;
714  std::string fname;
715  std::ofstream ofs;
716 
717  int i(1);
718  while (i < argc)
719  {
720  std::string arg(argv[i]);
721  std::string next_arg;
722  if (i + 1 < argc) next_arg = argv[i + 1];
723  else next_arg = "";
724 
725  if (arg == "--text") { format = TEXT_OUT; break; }
726  if (arg == "--xml")
727  {
728  if (next_arg == "")
729  {
730  fname = argv[0];
731  fname += ".xml";
732  }
733  else
734  {
735  fname = next_arg;
736  }
737  format = XML_OUT;
738  ofs.open(fname.c_str());
739  }
740  if ( arg == "--compiler" ) { format = COMPILER_OUT; break; }
741  if ( arg == "--cerr" ) { target = 1; break; }
742  if ( arg == "--xsl" )
743  {
744  if (next_arg == "") xsl = "default.xsl";
745  else xsl = next_arg;
746  }
747  if ( arg == "--namespace" )
748  {
749  if (next_arg == "")
750  {
751  std::cerr << "no namespace specified" << std::endl;
752  exit(1);
753  }
754  else
755  {
756  xsl = next_arg;
757  }
758  }
759  ++i;
760  }
761  CppUnit::TextUi::TestRunner runner;
762  if ( ns.empty() )
763  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry().makeTest());
764  else
765  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry(ns).makeTest());
766  CppUnit::Outputter* outputter = 0;
767  std::ostream* stream = target ? &std::cerr : &std::cout;
768  switch ( format )
769  {
770  case TEXT_OUT :
771  outputter = new CppUnit::TextOutputter(&runner.result(),*stream);
772  break;
773  case XML_OUT :
774  std::cout << "XML_OUT" << std::endl;
775  outputter = new CppUnit::XmlOutputter(&runner.result(),
776  ofs, "shift_jis");
777  static_cast<CppUnit::XmlOutputter*>(outputter)->setStyleSheet(xsl);
778  break;
779  case COMPILER_OUT :
780  outputter = new CppUnit::CompilerOutputter(&runner.result(),*stream);
781  break;
782  }
783  runner.setOutputter(outputter);
784  runner.run();
785  return 0; // runner.run() ? 0 : 1;
786 }
787 #endif // MAIN
788 #endif // InPort_cpp
SDOPackage::NameValue newNV(const char *name, Value value)
Create NameValue.
Definition: NVUtil.h:79
virtual void init(const coil::Properties &prop)
Set the buffer.
ConnectorListeners class.
virtual DataType * wptr(long int n=0)
Get the writing pointer.
int main(int argc, char **argv)
virtual void activate()=0
Connector activation.
CORBA Consumer class.
OutPortConnector base class.
DataPortStatus class.
CPPUNIT_TEST_SUITE_REGISTRATION(OutPortPullConnector::OutPortPullConnectorTests)
ConnectorListener class.
virtual size_t writable() const
Get a writable number.
virtual ReturnCode length(size_t n)
Set the buffer length.
void addListener(ConnectorDataListener *listener, bool autoclean)
Add the listener.
std::vector< std::pair< std::string, std::string > > NVList
Definition: IRTC.h:67
void test_OutPortPullConnector()
Constructor メソッドテスト
void log(const std::string &msg)
ConnectorListenerHolder connector_[CONNECTOR_LISTENER_NUM]
ConnectorListenerType listener array The ConnectorListenerType listener is stored.
virtual CdrBufferBase * getBuffer()=0
Getting Buffer.
virtual DataType * rptr(long int n=0)
Get the reading pointer.
virtual void operator()(const RTC::ConnectorInfo &info)
Virtual Callback method.
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
void publishInterfaceProfile(SDOPackage::NVList &properties)
Publish InterfaceProfile information.
void init(coil::Properties &prop)
Initializing configuration.
void set_read_return_value(::RTC::BufferStatus::Enum value)
Typename function.
void addListener(ConnectorListener *listener, bool autoclean)
Add the listener.
virtual size_t length(void) const
Get the buffer length.
Enum
DataPortStatus return codes.
Definition: BufferStatus.h:84
virtual bool empty(void) const
Check on whether the buffer is empty.
virtual ReturnCode put(const DataType &value)
Write data into the buffer.
void setConnector(RTC::OutPortConnector *connector)
set Connector
Connector base class.
#define BUFFERSTATUS_ENUM
Importing RTC::BufferStatus macro.
Definition: BufferStatus.h:157
ConnectorDataListenerHolder connectorData_[CONNECTOR_DATA_LISTENER_NUM]
ConnectorDataListenerType listener array The ConnectorDataListenerType listener is stored...
virtual ReturnCode write(const cdrMemoryStream &data)=0
Destructor.
void test_disconnect_getBuffer()
disconnect メソッドテスト
virtual ReturnCode read(DataType &value, long int sec=-1, long int nsec=-1)
Read data from the buffer.
void copyToProperties(coil::Properties &prop, const SDOPackage::NVList &nv)
Copy NVList to the Proeprties.
Definition: NVUtil.cpp:137
virtual ReturnCode write(const DataType &value, long int sec=-1, long int nsec=-1)
Write data into the buffer.
ConnectorDataListenerT class.
void test_activate_deactivate()
activate メソッドテスト
NameValue and NVList utility functions.
CORBA sequence utility template functions.
virtual ReturnCode disconnect()=0
Disconnect connection.
std::string name
Connection name.
int countLog(const std::string &msg)
void log(const std::string &msg)
OutPortProvider.
::RTC::BufferStatus::Enum ReturnCode
prop
Organization::get_organization_property ();.
Publisher base class.
RTC::Port implementation for InPort.
InPortBase base class.
Class represents a set of properties.
Definition: Properties.h:101
virtual ReturnCode advanceWptr(long int n=1)
Forward n writing pointers.
void setListener(RTC::ConnectorInfo &info, RTC::ConnectorListeners *listeners)
Set the listener.
bool subscribeInterface(const SDOPackage::NVList &properties)
OutPortPull type connector class.
RingBufferMock< cdrMemoryStream > CdrRingBufferMock
::OutPortBase::Logger logger
void push_back(CorbaSequence &seq, SequenceElement elem)
Push the new element back to the CORBA sequence.
BUFFERSTATUS_ENUM RingBufferMock(long int length=8)
OutPortPullConnector class.
void setBuffer(RTC::CdrBufferBase *buffer)
Setting outside buffer&#39;s pointer.
Properties & getNode(const std::string &key)
Get node of properties.
Definition: Properties.cpp:455
def test_activate_deactivate(message, arg0, arg1, arg2)
Only activation and deactivation are repeated.
virtual bool full(void) const
Check on whether the buffer is full.
void unsubscribeInterface(const SDOPackage::NVList &properties)
coil::vstring refToVstring(const CorbaRefSequence &objlist)
virtual void operator()(const RTC::ConnectorInfo &info, const RTC::TimedLong &data)
Virtual Callback method.
BufferBase abstract class.
Definition: BufferBase.h:104
InPortConsumer class.
virtual size_t readable() const
Write data into the buffer.
virtual ReturnCode advanceRptr(long int n=1)
Forward n reading pointers.
RTC&#39;s Port administration class.
RTC::InPortConsumer::ReturnCode put(const cdrMemoryStream &data)
virtual ReturnCode reset()
Reset the buffer status.


openrtm_aist
Author(s): Noriaki Ando
autogenerated on Mon Jun 10 2019 14:07:54