InPortPullConnectorTests.cpp
Go to the documentation of this file.
1 // -*- C++ -*-
22 #ifndef InPortPullConnector_cpp
23 #define InPortPullConnector_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/OutPortConsumer.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 
112  m_log.push_back(msg);
113  }
114 
115  int countLog(const std::string& msg)
116  {
117  int count = 0;
118  for (int i = 0; i < (int) m_log.size(); ++i)
119  {
120  if (m_log[i] == msg) ++count;
121  }
122  return count;
123  }
124 
125  private:
126  std::vector<std::string> m_log;
127  };
133  template <class DataType>
135  : public RTC::BufferBase<DataType>
136  {
137  public:
139  RingBufferMock(long int length = 8)
140  {
141  m_logger = NULL;
142  logger.log("RingBufferMock::Constructor");
143  m_read_return_value = BUFFER_OK;
144  m_write_return_value = BUFFER_OK;
145  }
146  virtual ~RingBufferMock(void)
147  {
148  }
149 
150 
156  {
157  m_read_return_value = value;
158  }
164  {
165  m_write_return_value = value;
166  }
171  virtual void init(const coil::Properties& prop)
172  {
173  }
178  virtual size_t length(void) const
179  {
180  return 0;
181  }
186  virtual ReturnCode length(size_t n)
187  {
188  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
189  }
194  virtual ReturnCode reset()
195  {
196  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
197  }
202  virtual DataType* wptr(long int n = 0)
203  {
204  return &m_data;
205  }
210  virtual ReturnCode advanceWptr(long int n = 1)
211  {
212  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
213  }
218  virtual ReturnCode put(const DataType& value)
219  {
220  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
221  }
226  virtual ReturnCode write(const DataType& value,
227  long int sec = -1, long int nsec = -1)
228  {
229  if (m_logger != NULL)
230  {
231  m_logger->log("RingBufferMock::write");
232  }
233  logger.log("RingBufferMock::write");
234  return m_write_return_value; //BUFFER_OK;
235  }
240  virtual size_t writable() const
241  {
242  return 0;
243  }
248  virtual bool full(void) const
249  {
250  return true;
251  }
256  virtual DataType* rptr(long int n = 0)
257  {
258  return &m_data;
259  }
264  virtual ReturnCode advanceRptr(long int n = 1)
265  {
266  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
267  }
272  virtual ReturnCode get(DataType& value)
273  {
274  return ::RTC::BufferStatus::BUFFER_OK; //BUFFER_OK;
275  }
280  virtual DataType& get()
281  {
282  return m_data;
283  }
288  virtual ReturnCode read(DataType& value,
289  long int sec = -1, long int nsec = -1)
290  {
291  if (m_logger != NULL)
292  {
293  m_logger->log("RingBufferMock::read");
294  }
295  logger.log("RingBufferMock::read");
296  return m_read_return_value; //BUFFER_OK;
297  }
302  virtual size_t readable() const
303  {
304  return 0;
305  }
310  virtual bool empty(void) const
311  {
312  return true;
313  }
319  {
320  m_logger = logger;
321  }
322 
323  static Logger logger;
324  private:
325  DataType m_data;
326  std::vector<DataType> m_buffer;
330  };
331 
332  template <class DataType>
335 
342  : public RTC::OutPortConsumer,
343  public RTC::CorbaConsumer< ::OpenRTM::OutPortCdr >
344  {
345 
346  public:
348  {
349  m_logger = NULL;
350  }
352  {
353  }
359  {
360  if (m_logger != NULL)
361  {
362  m_logger->log("OutPortCorbaCdrConsumerMock::setBuffer");
363  }
364  }
369  ::OpenRTM::PortStatus put(const ::OpenRTM::CdrData& data)
370  throw (CORBA::SystemException)
371  {
372  return ::OpenRTM::PORT_OK;
373  }
379  {
380  if (m_logger != NULL)
381  {
382  m_logger->log("OutPortCorbaCdrConsumerMock::init");
383  }
384  }
389  RTC::OutPortConsumer::ReturnCode put(const cdrMemoryStream& data)
390  {
391  return PORT_OK;
392  }
398  {
399  return;
400  }
401 
406  bool subscribeInterface(const SDOPackage::NVList& properties)
407  {
408 
409  return true;;
410  }
411 
416  void unsubscribeInterface(const SDOPackage::NVList& properties)
417  {
418  }
423  virtual ReturnCode get(cdrMemoryStream& data)
424  {
425  if (m_logger != NULL)
426  {
427  m_logger->log("OutPortCorbaCdrConsumerMock::get");
428  }
429  return PORT_OK;
430  }
431 
432 
438  {
439  m_logger = logger;
440  }
441 
443  {
444  }
445 
446  private:
448 
449  };
456  : public CppUnit::TestFixture
457  {
458  CPPUNIT_TEST_SUITE(InPortPullConnectorTests);
459 
460  CPPUNIT_TEST(test_InPortPullConnector);
461  CPPUNIT_TEST(test_read);
462  CPPUNIT_TEST(test_disconnect);
463  CPPUNIT_TEST_SUITE_END();
464 
465  private:
466  CORBA::ORB_ptr m_pORB;
467  PortableServer::POA_ptr m_pPOA;
468 
469 
470  public:
472 
477  {
478 
479  int argc(0);
480  char** argv(NULL);
481  m_pORB = CORBA::ORB_init(argc, argv);
482  m_pPOA = PortableServer::POA::_narrow(
483  m_pORB->resolve_initial_references("RootPOA"));
484  m_pPOA->the_POAManager()->activate();
485  }
486 
491  {
492  }
493 
497  virtual void setUp()
498  {
499  //ConnectorDataListeners
501  new DataListener("ON_BUFFER_WRITE"), true);
503  new DataListener("ON_BUFFER_FULL"), true);
505  new DataListener("ON_BUFFER_WRITE_TIMEOUT"), true);
507  new DataListener("ON_BUFFER_OVERWRITE"), true);
509  new DataListener("ON_BUFFER_READ"), true);
511  new DataListener("ON_SEND"), true);
513  new DataListener("ON_RECEIVED"), true);
515  new DataListener("ON_RECEIVER_FULL"), true);
517  new DataListener("ON_RECEIVER_TIMEOUT"), true);
519  new DataListener("ON_RECEIVER_ERROR"), true);
520 
521  //ConnectorListeners
523  new ConnListener("ON_BUFFER_EMPTY"), true);
525  new ConnListener("ON_BUFFER_READ_TIMEOUT"), true);
527  new ConnListener("ON_SENDER_EMPTY"), true);
529  new ConnListener("ON_SENDER_TIMEOUT"), true);
531  new ConnListener("ON_SENDER_ERROR"), true);
533  new ConnListener("ON_CONNECT"), true);
535  new ConnListener("ON_DISCONNECT"), true);
536  }
537 
541  virtual void tearDown()
542  {
543  }
544 
550  {
552  addFactory("ring_buffer_mock",
553  coil::Creator<RTC::CdrBufferBase, CdrRingBufferMock>,
554  coil::Destructor<RTC::CdrBufferBase, CdrRingBufferMock>);
555 
556  RTC::ConnectorProfile prof;
557  CORBA_SeqUtil::push_back(prof.properties,
558  NVUtil::newNV("dataport.buffer_type",
559  "ring_buffer_mock"));
560  // prop: [port.outport].
562  {
563  coil::Properties conn_prop;
564  NVUtil::copyToProperties(conn_prop, prof.properties);
565  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
566  }
568  Logger logger;
569  consumer->setLogger(&logger);
570  RTC::ConnectorInfo profile_new(prof.name,
571  prof.connector_id,
572  CORBA_SeqUtil::refToVstring(prof.ports),
573  prop);
574  RTC::InPortConnector* connector(0);
575  CPPUNIT_ASSERT_EQUAL(0,
576  logger.countLog("OutPortCorbaCdrConsumerMock::setBuffer"));
577  CPPUNIT_ASSERT_EQUAL(0,
578  CdrRingBufferMock::logger.countLog("RingBufferMock::Constructor"));
579  connector = new RTC::InPortPullConnector(profile_new, consumer, m_listeners);
580  CPPUNIT_ASSERT_EQUAL(1,
581  logger.countLog("OutPortCorbaCdrConsumerMock::setBuffer"));
582  CPPUNIT_ASSERT_EQUAL(1,
583  CdrRingBufferMock::logger.countLog("RingBufferMock::Constructor"));
584 
585  //consumer
586  delete connector;
587 
588  //provider
589  RTC::InPortConnector* connector_err(0);
590  try {
591  RTC::ConnectorProfile prof_err;
592  // prop: [port.outport].
593  {
594  coil::Properties conn_prop;
595  NVUtil::copyToProperties(conn_prop, prof_err.properties);
596  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
597  }
598  RTC::ConnectorInfo profile_err(prof_err.name,
599  prof_err.connector_id,
600  CORBA_SeqUtil::refToVstring(prof_err.ports),
601  prop);
602  connector_err = new RTC::InPortPullConnector(profile_err, NULL, m_listeners);
603  CPPUNIT_FAIL("The exception was not thrown. ");
604  }
605  catch(std::bad_alloc& e)
606  {
607  }
608  catch(...)
609  {
610  CPPUNIT_FAIL("The exception not intended was thrown .");
611  }
612 
613  delete connector_err;
614  delete consumer;
615 
616  }
621  void test_read()
622  {
623  CdrRingBufferMock* pbuffer = new CdrRingBufferMock();
624 
625  RTC::ConnectorProfile prof;
626  CORBA_SeqUtil::push_back(prof.properties,
627  NVUtil::newNV("dataport.buffer_type",
628  "ring_buffer_mock"));
629  // prop: [port.outport].
631  {
632  coil::Properties conn_prop;
633  NVUtil::copyToProperties(conn_prop, prof.properties);
634  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
635  }
637  Logger logger;
638  consumer->setLogger(&logger);
639  RTC::ConnectorInfo profile_new(prof.name,
640  prof.connector_id,
641  CORBA_SeqUtil::refToVstring(prof.ports),
642  prop);
643  RTC::InPortConnector* connector(0);
644  connector = new RTC::InPortPullConnector(profile_new, consumer, m_listeners, pbuffer);
645  cdrMemoryStream cdr;
647  CPPUNIT_ASSERT_EQUAL(0,
648  logger.countLog("OutPortCorbaCdrConsumerMock::get"));
649  ret = connector->read(cdr);
650 
651  CPPUNIT_ASSERT_EQUAL(1,
652  logger.countLog("OutPortCorbaCdrConsumerMock::get"));
653 
655  ret = connector->read(cdr);
656  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::PORT_OK,ret);
657 
658  delete connector;
659  delete consumer;
660  delete pbuffer;
661 
662  }
668  {
670  addFactory("ring_buffer_mock",
671  coil::Creator<RTC::CdrBufferBase, CdrRingBufferMock>,
672  coil::Destructor<RTC::CdrBufferBase, CdrRingBufferMock>);
673 
674  RTC::ConnectorProfile prof;
675  CORBA_SeqUtil::push_back(prof.properties,
676  NVUtil::newNV("dataport.buffer_type",
677  "ring_buffer_mock"));
678  // prop: [port.outport].
680  {
681  coil::Properties conn_prop;
682  NVUtil::copyToProperties(conn_prop, prof.properties);
683  prop << conn_prop.getNode("dataport"); // marge ConnectorProfile
684  }
686  Logger logger;
687  consumer->setLogger(&logger);
688  RTC::ConnectorInfo profile_new(prof.name,
689  prof.connector_id,
690  CORBA_SeqUtil::refToVstring(prof.ports),
691  prop);
692  RTC::InPortConnector* connector(0);
693  connector = new RTC::InPortPullConnector(profile_new, consumer, m_listeners);
694 
696  CPPUNIT_ASSERT_EQUAL(RTC::ConnectorBase::PORT_OK,ret);
697 
698  delete connector;
699  delete consumer;
700 
701  }
702  };
703 }; // namespace InPortPullConnector
704 
705 /*
706  * Register test suite
707  */
709 
710 #ifdef LOCAL_MAIN
711 int main(int argc, char* argv[])
712 {
713 
714  FORMAT format = TEXT_OUT;
715  int target = 0;
716  std::string xsl;
717  std::string ns;
718  std::string fname;
719  std::ofstream ofs;
720 
721  int i(1);
722  while (i < argc)
723  {
724  std::string arg(argv[i]);
725  std::string next_arg;
726  if (i + 1 < argc) next_arg = argv[i + 1];
727  else next_arg = "";
728 
729  if (arg == "--text") { format = TEXT_OUT; break; }
730  if (arg == "--xml")
731  {
732  if (next_arg == "")
733  {
734  fname = argv[0];
735  fname += ".xml";
736  }
737  else
738  {
739  fname = next_arg;
740  }
741  format = XML_OUT;
742  ofs.open(fname.c_str());
743  }
744  if ( arg == "--compiler" ) { format = COMPILER_OUT; break; }
745  if ( arg == "--cerr" ) { target = 1; break; }
746  if ( arg == "--xsl" )
747  {
748  if (next_arg == "") xsl = "default.xsl";
749  else xsl = next_arg;
750  }
751  if ( arg == "--namespace" )
752  {
753  if (next_arg == "")
754  {
755  std::cerr << "no namespace specified" << std::endl;
756  exit(1);
757  }
758  else
759  {
760  xsl = next_arg;
761  }
762  }
763  ++i;
764  }
765  CppUnit::TextUi::TestRunner runner;
766  if ( ns.empty() )
767  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry().makeTest());
768  else
769  runner.addTest(CppUnit::TestFactoryRegistry::getRegistry(ns).makeTest());
770  CppUnit::Outputter* outputter = 0;
771  std::ostream* stream = target ? &std::cerr : &std::cout;
772  switch ( format )
773  {
774  case TEXT_OUT :
775  outputter = new CppUnit::TextOutputter(&runner.result(),*stream);
776  break;
777  case XML_OUT :
778  std::cout << "XML_OUT" << std::endl;
779  outputter = new CppUnit::XmlOutputter(&runner.result(),
780  ofs, "shift_jis");
781  static_cast<CppUnit::XmlOutputter*>(outputter)->setStyleSheet(xsl);
782  break;
783  case COMPILER_OUT :
784  outputter = new CppUnit::CompilerOutputter(&runner.result(),*stream);
785  break;
786  }
787  runner.setOutputter(outputter);
788  runner.run();
789  return 0; // runner.run() ? 0 : 1;
790 }
791 #endif // MAIN
792 #endif // InPort_cpp
SDOPackage::NameValue newNV(const char *name, Value value)
Create NameValue.
Definition: NVUtil.h:79
ConnectorListeners class.
virtual size_t readable() const
Write data into the buffer.
virtual DataType * wptr(long int n=0)
Get the writing pointer.
int main(int argc, char **argv)
virtual ReturnCode put(const DataType &value)
Write data into the buffer.
virtual DataType * rptr(long int n=0)
Get the reading pointer.
InPortConnector base class.
CORBA Consumer class.
DataPortStatus class.
virtual ReturnCode read(cdrMemoryStream &data)=0
Destructor.
virtual void operator()(const RTC::ConnectorInfo &info, const RTC::TimedLong &data)
Virtual Callback method.
virtual void init(const coil::Properties &prop)
Set the buffer.
ConnectorListener class.
void test_InPortPullConnector()
Constructor メソッドテスト
virtual ReturnCode advanceWptr(long int n=1)
Forward n writing pointers.
virtual ReturnCode read(DataType &value, long int sec=-1, long int nsec=-1)
Read data from the buffer.
void addListener(ConnectorDataListener *listener, bool autoclean)
Add the listener.
CPPUNIT_TEST_SUITE_REGISTRATION(InPortPullConnector::InPortPullConnectorTests)
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.
InPortPullConnector class.
RTC::ReturnCode_t ret(RTC::Local::ReturnCode_t r)
void setListener(RTC::ConnectorInfo &info, RTC::ConnectorListeners *listeners)
Set the listener.
void test_disconnect()
disconnect メソッドテスト
virtual bool full(void) const
Check on whether the buffer is full.
Typename function.
OutPortConsumer class.
void addListener(ConnectorListener *listener, bool autoclean)
Add the listener.
static GlobalFactory< AbstractClass, Identifier, Compare, Creator, Destructor > & instance()
Create instance.
Definition: Singleton.h:131
Enum
DataPortStatus return codes.
Definition: BufferStatus.h:84
RTComponent manager class.
void log(const std::string &msg)
void unsubscribeInterface(const SDOPackage::NVList &properties)
Unsubscribe the data receive notification.
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 set_write_return_value(::RTC::BufferStatus::Enum value)
virtual bool empty(void) const
Check on whether the buffer is empty.
void copyToProperties(coil::Properties &prop, const SDOPackage::NVList &nv)
Copy NVList to the Proeprties.
Definition: NVUtil.cpp:137
ConnectorDataListenerT class.
::OpenRTM::PortStatus put(const ::OpenRTM::CdrData &data)
Buffer abstract class.
virtual size_t writable() const
Get a writable number.
NameValue and NVList utility functions.
bool subscribeInterface(const SDOPackage::NVList &properties)
Subscribe the data receive notification.
CORBA sequence utility template functions.
std::string name
Connection name.
BUFFERSTATUS_ENUM RingBufferMock(long int length=8)
int countLog(const std::string &msg)
std::vector< std::string > m_log
::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 reset()
Reset the buffer status.
void set_read_return_value(::RTC::BufferStatus::Enum value)
virtual ReturnCode write(const DataType &value, long int sec=-1, long int nsec=-1)
Write data into the buffer.
RingBufferMock< cdrMemoryStream > CdrRingBufferMock
virtual size_t length(void) const
Get the buffer length.
void init(coil::Properties &prop)
Initializing configuration.
InPortPull type connector class.
::OutPortBase::Logger logger
void push_back(CorbaSequence &seq, SequenceElement elem)
Push the new element back to the CORBA sequence.
OutPortConsumer abstract class.
Properties & getNode(const std::string &key)
Get node of properties.
Definition: Properties.cpp:455
RTC::OutPortConsumer::ReturnCode put(const cdrMemoryStream &data)
coil::vstring refToVstring(const CorbaRefSequence &objlist)
BufferBase abstract class.
Definition: BufferBase.h:104
InPortConsumer class.
void setBuffer(RTC::BufferBase< cdrMemoryStream > *buffer)
Setting outside buffer&#39;s pointer.
RTC&#39;s Port administration class.
virtual void operator()(const RTC::ConnectorInfo &info)
Virtual Callback method.
void publishInterfaceProfile(SDOPackage::NVList &properties)
virtual ReturnCode length(size_t n)
Set the buffer length.
virtual ReturnCode advanceRptr(long int n=1)
Forward n reading pointers.


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