InPortPushConnectorTests.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
22 #ifndef InPortPushConnector_cpp
23 #define InPortPushConnector_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 #include <rtm/BufferBase.h>
49 #include <rtm/InPortProvider.h>
50 #include <rtm/Manager.h>
51 
57 {
58 
60  : public RTC::ConnectorDataListenerT<RTC::TimedLong>
61  {
62  public:
63  DataListener(const char* name) : m_name(name) {}
64  virtual ~DataListener()
65  {
66  //std::cout << "dtor of " << m_name << std::endl;
67  }
68 
69  virtual void operator()(const RTC::ConnectorInfo& info,
70  const RTC::TimedLong& data)
71  {
72  //std::cout << "------------------------------" << std::endl;
73  //std::cout << "Data Listener: " << m_name << std::endl;
74  //std::cout << "Profile::name: " << info.name << std::endl;
75  //std::cout << "------------------------------" << std::endl;
76  };
77  std::string m_name;
78  };
79 
80 
82  : public RTC::ConnectorListener
83  {
84  public:
85  ConnListener(const char* name) : m_name(name) {}
86  virtual ~ConnListener()
87  {
88  //std::cout << "dtor of " << m_name << std::endl;
89  }
90 
91  virtual void operator()(const RTC::ConnectorInfo& info)
92  {
93  std::cout << "------------------------------" << std::endl;
94  std::cout << "Connector Listener: " << m_name << std::endl;
95  std::cout << "Profile::name: " << info.name << std::endl;
96  std::cout << "------------------------------" << std::endl;
97  };
98  std::string m_name;
99  };
100 
106  class Logger
107  {
108  public:
109  void log(const std::string& msg)
110  {
111  m_log.push_back(msg);
112  }
113 
114  int countLog(const std::string& msg)
115  {
116  int count = 0;
117  for (int i = 0; i < (int) m_log.size(); ++i)
118  {
119  if (m_log[i] == msg) ++count;
120  }
121  return count;
122  }
123 
124  private:
125  std::vector<std::string> m_log;
126  };
132  template <class DataType>
134  : public RTC::BufferBase<DataType>
135  {
136  public:
138  RingBufferMock(long int length = 8)
139  {
140  m_logger = NULL;
141  logger.log("RingBufferMock::Constructor");
142  m_read_return_value = BUFFER_OK;
143  }
144  virtual ~RingBufferMock(void)
145  {
146  }
147 
148 
154  {
155  m_read_return_value = value;
156  }
161  virtual void init(const coil::Properties& prop)
162  {
163  }
168  virtual size_t length(void) const
169  {
170  return 0;
171  }
176  virtual ReturnCode length(size_t n)
177  {
178  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
179  }
184  virtual ReturnCode reset()
185  {
186  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
187  }
192  virtual DataType* wptr(long int n = 0)
193  {
194  return &m_data;
195  }
200  virtual ReturnCode advanceWptr(long int n = 1)
201  {
202  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
203  }
208  virtual ReturnCode put(const DataType& value)
209  {
210  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
211  }
216  virtual ReturnCode write(const DataType& value,
217  long int sec = -1, long int nsec = -1)
218  {
219  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
220  }
225  virtual size_t writable() const
226  {
227  return 0;
228  }
233  virtual bool full(void) const
234  {
235  return true;
236  }
241  virtual DataType* rptr(long int n = 0)
242  {
243  return &m_data;
244  }
249  virtual ReturnCode advanceRptr(long int n = 1)
250  {
251  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
252  }
257  virtual ReturnCode get(DataType& value)
258  {
259  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
260  }
265  virtual DataType& get()
266  {
267  return m_data;
268  }
273  virtual ReturnCode read(DataType& value,
274  long int sec = -1, long int nsec = -1)
275  {
276  if (m_logger != NULL)
277  {
278  m_logger->log("RingBufferMock::read");
279  }
280  logger.log("RingBufferMock::read");
281  return m_read_return_value; //BUFFER_OK;
282  }
287  virtual size_t readable() const
288  {
289  return 0;
290  }
295  virtual bool empty(void) const
296  {
297  return true;
298  }
304  {
305  m_logger = logger;
306  }
307 
308  static Logger logger;
309  private:
310  DataType m_data;
311  std::vector<DataType> m_buffer;
314  };
315  template <class DataType>
324  : public RTC::InPortProvider,
325  public virtual POA_OpenRTM::InPortCdr,
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("InPortCorbaCdrProviderMock::setBuffer");
346  }
347  }
352  ::OpenRTM::PortStatus put(const ::OpenRTM::CdrData& data)
353  throw (CORBA::SystemException)
354  {
355  return ::OpenRTM::PORT_OK;
356  }
362  {
363  if (m_logger != NULL)
364  {
365  m_logger->log("InPortCorbaCdrProviderMock::init");
366  }
367  }
372  RTC::InPortConsumer::ReturnCode put(const cdrMemoryStream& data)
373  {
374  return PORT_OK;
375  }
381  {
382  return;
383  }
384 
389  bool subscribeInterface(const SDOPackage::NVList& properties)
390  {
391 
392  return true;;
393  }
394 
399  void unsubscribeInterface(const SDOPackage::NVList& properties)
400  {
401  }
402 
408  {
409  m_logger = logger;
410  }
411 
413  {
414  }
416  {
417  }
418 
419  private:
421 
422  };
429  : public CppUnit::TestFixture
430  {
431  CPPUNIT_TEST_SUITE(InPortPushConnectorTests);
432 
433  CPPUNIT_TEST(test_InPortPushConnector);
434  CPPUNIT_TEST(test_read);
435  CPPUNIT_TEST(test_disconnect);
436 
437  CPPUNIT_TEST_SUITE_END();
438 
439  private:
440  CORBA::ORB_ptr m_pORB;
441  PortableServer::POA_ptr m_pPOA;
442 
443 
444  public:
446 
451  {
452 
453  int argc(0);
454  char** argv(NULL);
455  m_pORB = CORBA::ORB_init(argc, argv);
456  m_pPOA = PortableServer::POA::_narrow(
457  m_pORB->resolve_initial_references("RootPOA"));
458  m_pPOA->the_POAManager()->activate();
459 
460 
461 
462  }
463 
468  {
469  }
470 
474  virtual void setUp()
475  {
476  //ConnectorDataListeners
478  new DataListener("ON_BUFFER_WRITE"), true);
480  new DataListener("ON_BUFFER_FULL"), true);
482  new DataListener("ON_BUFFER_WRITE_TIMEOUT"), true);
484  new DataListener("ON_BUFFER_OVERWRITE"), true);
486  new DataListener("ON_BUFFER_READ"), true);
488  new DataListener("ON_SEND"), true);
490  new DataListener("ON_RECEIVED"), true);
492  new DataListener("ON_RECEIVER_FULL"), true);
494  new DataListener("ON_RECEIVER_TIMEOUT"), true);
496  new DataListener("ON_RECEIVER_ERROR"), true);
497 
498  //ConnectorListeners
500  new ConnListener("ON_BUFFER_EMPTY"), true);
502  new ConnListener("ON_BUFFER_READ_TIMEOUT"), true);
504  new ConnListener("ON_SENDER_EMPTY"), true);
506  new ConnListener("ON_SENDER_TIMEOUT"), true);
508  new ConnListener("ON_SENDER_ERROR"), true);
510  new ConnListener("ON_CONNECT"), true);
512  new ConnListener("ON_DISCONNECT"), true);
513  }
514 
518  virtual void tearDown()
519  {
520  }
521 
527  {
529  addFactory("ring_buffer_mock",
530  coil::Creator<RTC::CdrBufferBase, CdrRingBufferMock>,
531  coil::Destructor<RTC::CdrBufferBase, CdrRingBufferMock>);
532 
533  RTC::ConnectorProfile prof;
534  CORBA_SeqUtil::push_back(prof.properties,
535  NVUtil::newNV("dataport.buffer_type",
536  "ring_buffer_mock"));
537  // prop: [port.outport].
539  {
540  coil::Properties conn_prop;
541  NVUtil::copyToProperties(conn_prop, prof.properties);
542  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
543  }
545  Logger logger;
546  provider->setLogger(&logger);
547  RTC::ConnectorInfo profile_new(prof.name,
548  prof.connector_id,
549  CORBA_SeqUtil::refToVstring(prof.ports),
550  prop);
551  RTC::InPortConnector* connector(0);
552  CPPUNIT_ASSERT_EQUAL(0,
553  logger.countLog("InPortCorbaCdrProviderMock::init"));
554  CPPUNIT_ASSERT_EQUAL(0,
555  logger.countLog("InPortCorbaCdrProviderMock::setBuffer"));
556  CPPUNIT_ASSERT_EQUAL(0,
557  CdrRingBufferMock::logger.countLog("RingBufferMock::Constructor"));
558  connector = new RTC::InPortPushConnector(profile_new, provider, m_listeners);
559  CPPUNIT_ASSERT_EQUAL(1,
560  logger.countLog("InPortCorbaCdrProviderMock::init"));
561  CPPUNIT_ASSERT_EQUAL(1,
562  logger.countLog("InPortCorbaCdrProviderMock::setBuffer"));
563  CPPUNIT_ASSERT_EQUAL(1,
564  CdrRingBufferMock::logger.countLog("RingBufferMock::Constructor"));
565 
566  //consumer
567  delete connector;
568 
569  //provider
570  RTC::InPortConnector* connector_err(0);
571  try {
572  RTC::ConnectorProfile prof_err;
573  // prop: [port.outport].
574  {
575  coil::Properties conn_prop;
576  NVUtil::copyToProperties(conn_prop, prof_err.properties);
577  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
578  }
579  RTC::ConnectorInfo profile_err(prof_err.name,
580  prof_err.connector_id,
581  CORBA_SeqUtil::refToVstring(prof_err.ports),
582  prop);
583  connector_err = new RTC::InPortPushConnector(profile_err, NULL, m_listeners);
584  CPPUNIT_FAIL("The exception was not thrown. ");
585  }
586  catch(std::bad_alloc& e)
587  {
588  }
589  catch(...)
590  {
591  CPPUNIT_FAIL("The exception not intended was thrown .");
592  }
593  delete connector_err;
594  delete provider;
595 
596  }
601  void test_read()
602  {
603  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
604 
605  RTC::ConnectorProfile prof;
606  CORBA_SeqUtil::push_back(prof.properties,
607  NVUtil::newNV("dataport.buffer_type",
608  "ring_buffer_mock"));
609  // prop: [port.outport].
611  {
612  coil::Properties conn_prop;
613  NVUtil::copyToProperties(conn_prop, prof.properties);
614  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
615  }
617  Logger logger;
618  provider->setLogger(&logger);
619  RTC::ConnectorInfo profile_new(prof.name,
620  prof.connector_id,
621  CORBA_SeqUtil::refToVstring(prof.ports),
622  prop);
623  RTC::InPortConnector* connector(0);
624  connector = new RTC::InPortPushConnector(profile_new, provider, m_listeners, pbuffer);
625  cdrMemoryStream cdr;
626  CPPUNIT_ASSERT_EQUAL(0,
627  CdrRingBufferMock::logger.countLog("RingBufferMock::read"));
628  connector->read(cdr);
629  CPPUNIT_ASSERT_EQUAL(1,
630  CdrRingBufferMock::logger.countLog("RingBufferMock::read"));
631 
634  ret = connector->read(cdr);
635  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::PORT_OK,ret);
636 
638  ret = connector->read(cdr);
639  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::BUFFER_EMPTY,ret);
640 
642  ret = connector->read(cdr);
643  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::BUFFER_TIMEOUT,ret);
644 
646  ret = connector->read(cdr);
647  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::PRECONDITION_NOT_MET,ret);
648 
649  delete connector;
650  delete provider;
651  delete pbuffer;
652 
653  }
659  {
661  addFactory("ring_buffer_mock",
662  coil::Creator<RTC::CdrBufferBase, CdrRingBufferMock>,
663  coil::Destructor<RTC::CdrBufferBase, CdrRingBufferMock>);
664 
665  RTC::ConnectorProfile prof;
666  CORBA_SeqUtil::push_back(prof.properties,
667  NVUtil::newNV("dataport.buffer_type",
668  "ring_buffer_mock"));
669  // prop: [port.outport].
671  {
672  coil::Properties conn_prop;
673  NVUtil::copyToProperties(conn_prop, prof.properties);
674  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
675  }
677  Logger logger;
678  provider->setLogger(&logger);
679  RTC::ConnectorInfo profile_new(prof.name,
680  prof.connector_id,
681  CORBA_SeqUtil::refToVstring(prof.ports),
682  prop);
683  RTC::InPortConnector* connector(0);
684  connector = new RTC::InPortPushConnector(profile_new, provider, m_listeners);
685 
686  connector->disconnect();
687  cdrMemoryStream cdr;
688  RTC::ConnectorBase::ReturnCode ret = connector->read(cdr);
689  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::PRECONDITION_NOT_MET,ret);
690 
691  delete connector;
692  delete provider;
693 
694  }
695  };
696 }; // namespace InPortPushConnector
697 
698 /*
699  * Register test suite
700  */
702 
703 #ifdef LOCAL_MAIN
704 int main(int argc, char* argv[])
705 {
706 
707  FORMAT format = TEXT_OUT;
708  int target = 0;
709  std::string xsl;
710  std::string ns;
711  std::string fname;
712  std::ofstream ofs;
713 
714  int i(1);
715  while (i < argc)
716  {
717  std::string arg(argv[i]);
718  std::string next_arg;
719  if (i + 1 < argc) next_arg = argv[i + 1];
720  else next_arg = "";
721 
722  if (arg == "--text") { format = TEXT_OUT; break; }
723  if (arg == "--xml")
724  {
725  if (next_arg == "")
726  {
727  fname = argv[0];
728  fname += ".xml";
729  }
730  else
731  {
732  fname = next_arg;
733  }
734  format = XML_OUT;
735  ofs.open(fname.c_str());
736  }
737  if ( arg == "--compiler" ) { format = COMPILER_OUT; break; }
738  if ( arg == "--cerr" ) { target = 1; break; }
739  if ( arg == "--xsl" )
740  {
741  if (next_arg == "") xsl = "default.xsl";
742  else xsl = next_arg;
743  }
744  if ( arg == "--namespace" )
745  {
746  if (next_arg == "")
747  {
748  std::cerr << "no namespace specified" << std::endl;
749  exit(1);
750  }
751  else
752  {
753  xsl = next_arg;
754  }
755  }
756  ++i;
757  }
758  CppUnit::TextUi::TestRunner runner;
759  if ( ns.empty() )
760  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry().makeTest());
761  else
762  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry(ns).makeTest());
763  CppUnit::Outputter* outputter = 0;
764  std::ostream* stream = target ? &std::cerr : &std::cout;
765  switch ( format )
766  {
767  case TEXT_OUT :
768  outputter = new CppUnit::TextOutputter(&runner.result(),*stream);
769  break;
770  case XML_OUT :
771  std::cout << "XML_OUT" << std::endl;
772  outputter = new CppUnit::XmlOutputter(&runner.result(),
773  ofs, "shift_jis");
774  static_cast<CppUnit::XmlOutputter*>(outputter)->setStyleSheet(xsl);
775  break;
776  case COMPILER_OUT :
777  outputter = new CppUnit::CompilerOutputter(&runner.result(),*stream);
778  break;
779  }
780  runner.setOutputter(outputter);
781  runner.run();
782  return 0; // runner.run() ? 0 : 1;
783 }
784 #endif // MAIN
785 #endif // InPort_cpp
SDOPackage::NameValue newNV(const char *name, Value value)
Create NameValue.
Definition: NVUtil.h:79
InPortPushConnector class.
ConnectorListeners class.
int main(int argc, char **argv)
InPortConnector base class.
CORBA Consumer class.
DataPortStatus class.
virtual void operator()(const RTC::ConnectorInfo &info)
Virtual Callback method.
InPortProvider class.
virtual ReturnCode read(cdrMemoryStream &data)=0
Destructor.
virtual ReturnCode reset()
Reset the buffer status.
ConnectorListener class.
int countLog(const std::string &msg)
void addListener(ConnectorDataListener *listener, bool autoclean)
Add the listener.
std::vector< std::pair< std::string, std::string > > NVList
Definition: IRTC.h:67
void log(const std::string &msg)
ConnectorListenerHolder connector_[CONNECTOR_LISTENER_NUM]
ConnectorListenerType listener array The ConnectorListenerType listener is stored.
virtual size_t length(void) const
Get the buffer length.
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
void setBuffer(RTC::BufferBase< cdrMemoryStream > *buffer)
Setting outside buffer&#39;s pointer.
virtual bool full(void) const
Check on whether the buffer is full.
virtual ReturnCode put(const DataType &value)
Write data into the buffer.
Typename function.
void test_InPortPushConnector()
Constructor メソッドテスト
void addListener(ConnectorListener *listener, bool autoclean)
Add the listener.
virtual ReturnCode write(const DataType &value, long int sec=-1, long int nsec=-1)
Write data into the buffer.
static GlobalFactory< AbstractClass, Identifier, Compare, Creator, Destructor > & instance()
Create instance.
Definition: Singleton.h:131
Enum
DataPortStatus return codes.
Definition: BufferStatus.h:84
virtual void init(const coil::Properties &prop)
Set the buffer.
InPortProvider.
void publishInterfaceProfile(SDOPackage::NVList &properties)
Publish InterfaceProfile information.
RTComponent manager class.
virtual ReturnCode disconnect()=0
Disconnect connection.
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...
void copyToProperties(coil::Properties &prop, const SDOPackage::NVList &nv)
Copy NVList to the Proeprties.
Definition: NVUtil.cpp:137
std::vector< std::string > m_log
ConnectorDataListenerT class.
Buffer abstract class.
NameValue and NVList utility functions.
CORBA sequence utility template functions.
Push type connector class.
std::string name
Connection name.
void log(const std::string &msg)
::RTC::BufferStatus::Enum ReturnCode
void init(coil::Properties &prop)
Initializing configuration.
prop
Organization::get_organization_property ();.
Publisher base class.
RTC::Port implementation for InPort.
RingBufferMock< cdrMemoryStream > CdrRingBufferMock
InPortBase base class.
void setConnector(RTC::InPortConnector *connector)
set Connector
Class represents a set of properties.
Definition: Properties.h:101
BUFFERSTATUS_ENUM RingBufferMock(long int length=8)
virtual DataType * rptr(long int n=0)
Get the reading pointer.
virtual void operator()(const RTC::ConnectorInfo &info, const RTC::TimedLong &data)
Virtual Callback method.
void set_read_return_value(::RTC::BufferStatus::Enum value)
void unsubscribeInterface(const SDOPackage::NVList &properties)
bool subscribeInterface(const SDOPackage::NVList &properties)
::OutPortBase::Logger logger
void push_back(CorbaSequence &seq, SequenceElement elem)
Push the new element back to the CORBA sequence.
void test_disconnect()
disconnect メソッドテスト
Properties & getNode(const std::string &key)
Get node of properties.
Definition: Properties.cpp:455
virtual ReturnCode length(size_t n)
Set the buffer length.
virtual ReturnCode read(DataType &value, long int sec=-1, long int nsec=-1)
Read data from the buffer.
RTC::InPortConsumer::ReturnCode put(const cdrMemoryStream &data)
virtual bool empty(void) const
Check on whether the buffer is empty.
coil::vstring refToVstring(const CorbaRefSequence &objlist)
BufferBase abstract class.
Definition: BufferBase.h:104
InPortConsumer class.
virtual size_t writable() const
Get a writable number.
virtual ReturnCode advanceWptr(long int n=1)
Forward n writing pointers.
virtual size_t readable() const
Write data into the buffer.
RTC&#39;s Port administration class.
::OpenRTM::PortStatus put(const ::OpenRTM::CdrData &data)
void setListener(RTC::ConnectorInfo &info, RTC::ConnectorListeners *listeners)
Set the listener.
virtual DataType * wptr(long int n=0)
Get the writing pointer.
virtual ReturnCode advanceRptr(long int n=1)
Forward n reading pointers.
CPPUNIT_TEST_SUITE_REGISTRATION(InPortPushConnector::InPortPushConnectorTests)


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