[openrtm-commit:03165] r940 - in branches/RELENG_1_2/OpenRTM-aist-Python: . OpenRTM_aist OpenRTM_aist/ext/sdo/observer OpenRTM_aist/utils/rtcprof

openrtm @ openrtm.org openrtm @ openrtm.org
2018年 2月 8日 (木) 10:13:55 JST


Author: kawauchi
Date: 2018-02-08 10:13:55 +0900 (Thu, 08 Feb 2018)
New Revision: 940

Modified:
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CORBA_RTCUtil.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CPUAffinity.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ConfigAdmin.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/DefaultConfiguration.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Factory.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/FactoryInit.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPort.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortBase.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPullConnector.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPushConnector.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Manager.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerConfig.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerServant.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ModuleManager.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingManager.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingServiceNumberingPolicy.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NodeNumberingPolicy.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NumberingPolicy.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPort.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortBase.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortConnector.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPullConnector.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPushConnector.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Properties.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/StringUtil.py
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ext/sdo/observer/rtc.conf
   branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/utils/rtcprof/rtcprof.py
   branches/RELENG_1_2/OpenRTM-aist-Python/setup.py
Log:
[merge] r915-939 have been merged from trunk.

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CORBA_RTCUtil.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CORBA_RTCUtil.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CORBA_RTCUtil.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -242,7 +242,7 @@
 # @param rtc ÂоݤÎRT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @param ec_id ¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤ÎID
 # @return RTC¡¢EC¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹¤¬nil¤Î¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
-# nil¤Ç¤Ï¤Ê¤¤¾ì¹ç¤Ïdeactivate_component´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤Î¾ì¹ç¤Ï¥ê¥»¥Ã¥È¤¬À®¸ù
+# nil¤Ç¤Ï¤Ê¤¤¾ì¹ç¤Ïreset_component´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤Î¾ì¹ç¤Ï¥ê¥»¥Ã¥È¤¬À®¸ù
 #
 # @else
 #
@@ -267,29 +267,28 @@
 # @brief ÂоݤÎRT¥³¥ó¥Ý¡¼¥Í¥ó¥È¤Î»ØÄꤷ¤¿¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤Ç¤Î¾õÂÖ¤ò¼èÆÀ
 #
 #
-# @param state RTC¤Î¾õÂÖ
 # @param rtc ÂоݤÎRT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @param ec_id ¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤ÎID
-# @return rtc¡¢ec¤¬nil¤Î¾ì¹ç¤ÏFalse¤òÊÖ¤¹¡£
-# nil¤Ç¤Ï¤Ê¤¤¾ì¹ç¤Ïstate[0]¤Ë¾õÂÖ¤òÂåÆþ¤·¤ÆTrue¤òÊÖ¤¹¡£
+# @return 1ÈÖÌܤÎÌá¤êÃͤȤ·¤Ærtc¡¢ec¤¬nil¤Î¾ì¹ç¤ÏFalse¤òÊÖ¤·¡¢¤½¤ì°Ê³°¤Î¾ì¹ç¤ÏTrue¤òÊÖ¤¹¡£
+# 2ÈÖÌܤÎÌá¤êÃͤȤ·¤Æ¾õÂÖ¤òÊÖ¤¹¡£
+# 
 #
 # @else
 #
 # @brief
-# @param state 
 # @param rtc
 # @param ec_id
 # @return 
 #
 # @endif
-def get_state(state, rtc, ec_id=0):
+def get_state(rtc, ec_id=0):
   if CORBA.is_nil(rtc):
-    return False
+    return False, RTC.CREATED_STATE
   ec = get_actual_ec(rtc, ec_id)
   if CORBA.is_nil(ec):
-    return False
-  state[0] = ec.get_component_state(rtc)
-  return True
+    return False, RTC.CREATED_STATE
+  state = ec.get_component_state(rtc)
+  return True, state
 
 ##
 # @if jp
@@ -311,9 +310,9 @@
 #
 # @endif
 def is_in_inactive(rtc, ec_id=0):
-  state = [None]
-  if get_state(state, rtc, ec_id):
-    if state[0] == RTC.INACTIVE_STATE:
+  ret, state = get_state(rtc, ec_id)
+  if ret:
+    if state == RTC.INACTIVE_STATE:
       return True
   return False
 
@@ -337,9 +336,9 @@
 #
 # @endif
 def is_in_active(rtc, ec_id=0):
-  state = [None]
-  if get_state(state, rtc, ec_id):
-    if state[0] == RTC.ACTIVE_STATE:
+  ret, state = get_state(rtc, ec_id)
+  if ret:
+    if state == RTC.ACTIVE_STATE:
       return True
   return False
 
@@ -363,9 +362,9 @@
 #
 # @endif
 def is_in_error(rtc, ec_id=0):
-  state = [None]
-  if get_state(state,rtc, ec_id):
-    if state[0] == RTC.ERROR_STATE:
+  ret, state = get_state(rtc, ec_id)
+  if ret:
+    if state == RTC.ERROR_STATE:
       return True
   return False
 
@@ -439,11 +438,12 @@
 ##
 # @if jp
 #
-# @brief RTC¤Î»ØÄêID¤Î¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤Î¼þ´ü¤ò¼èÆÀ
+# @brief RTC¤Î»ØÄêID¤Î¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤Î¼þ´ü¤òÀßÄê
 #
 # 
 # @param rtc ÂоݤÎRT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @param ec_id »ØÄê¤Î¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤ÎID
+# @param rate ¼Â¹Ô¼þ´ü
 # @return set_rate´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£
 # RTC_OK¤ÇÀßÄ꤬À®¸ù
 #
@@ -493,7 +493,7 @@
 # @param localcomp ÂоݤÎRT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @param othercomp ¼Â¹Ô¥³¥ó¥Æ¥­¥¹¥È¤È¤Î´ØÏ¢ÉÕ¤±¤ò²ò½ü¤¹¤ëRT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @return ec¤Î¼èÆÀ¤Ë¼ºÇÔ¤·¤¿¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
-# ¤½¤¦¤Ç¤Ê¤¤¾ì¹ç¤ÏremoveComponent´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤ÇÀܳÀ®¸ù¡£
+# ¤½¤¦¤Ç¤Ê¤¤¾ì¹ç¤ÏremoveComponent´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤Ç²ò½üÀ®¸ù¡£
 #
 # @else
 #
@@ -895,7 +895,7 @@
 # @param prop ÀßÄê
 # @param port0 ÂоݤΥݡ¼¥È1
 # @param port1 ÂоݤΥݡ¼¥È2
-# @return RTC¡¢EC¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹¤¬nil¤Î¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
+# @return ¥Ý¡¼¥È¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹¤¬nil¤Î¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
 # nil¤Ç¤Ï¤Ê¤¤¾ì¹ç¤Ïport0.connect´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤Î¾ì¹ç¤ÏÀܳ¤¬À®¸ù
 #
 # @else
@@ -929,8 +929,8 @@
 # 
 # @param name ¥³¥Í¥¯¥¿Ì¾
 # @param prop ÀßÄê
-# @param port0 ÂоݤΥݡ¼¥È
-# @param port1 ÂоݤΥݡ¼¥È¤Î¥ê¥¹¥È
+# @param port ÂоݤΥݡ¼¥È
+# @param target_ports ÂоݤΥݡ¼¥È¤Î¥ê¥¹¥È
 # @return Á´¤Æ¤ÎÀܳ¤¬À®¸ù¤·¤¿¾ì¹ç¤ÏRTC_OK¤òÊÖ¤¹¡£
 # connect´Ø¿ô¤¬RTC_OK°Ê³°¤òÊÖ¤·¤¿¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹¡£
 #
@@ -970,7 +970,7 @@
 #
 # @else
 # @class find_port
-# @brief ¥Ý¡¼¥È¤ò̾Á°¤«¤é¸¡º÷
+# @brief 
 #
 # @endif
 #
@@ -1135,7 +1135,7 @@
 # @endif
 def disconnect_by_portname_connector_name(port_name, conn_name):
   port_ref = get_port_by_url(port_name)
-  if port_ref == RTC.PortService._nil:
+  if CORBA.is_nil(port_ref):
     return RTC.BAD_PARAMETER
   
   conprof = port_ref.get_connector_profiles()
@@ -1177,7 +1177,7 @@
 # 
 # @param port_name ÂоݤΥݡ¼¥È̾
 # @param name ¥³¥Í¥¯¥¿ID
-# @return port¤¬nil¤Î¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
+# @return port¤¬Â¸ºß¤·¤Ê¤¤¾ì¹ç¤ÏBAD_PARAMETER¤òÊÖ¤¹
 # nil¤Ç¤Ï¤Ê¤¤¾ì¹ç¤Ïdisconnect´Ø¿ô¤ÎÌá¤êÃͤòÊÖ¤¹¡£RTC_OK¤Î¾ì¹ç¤ÏÀÚÃǤ¬À®¸ù
 #
 # @else
@@ -1343,7 +1343,7 @@
 # @brief »ØÄꤷ¤¿¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó¥»¥Ã¥È̾¡¢¥Ñ¥é¥á¡¼¥¿Ì¾¤Î¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó¥Ñ¥é¥á¡¼¥¿¤ò¼èÆÀ
 #
 # 
-# @param conf ¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó
+# @param rtc RT¥³¥ó¥Ý¡¼¥Í¥ó¥È
 # @param confset_name ¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó¥»¥Ã¥È̾
 # @param value_name ¥Ñ¥é¥á¡¼¥¿Ì¾
 # @return ¥Ñ¥é¥á¡¼¥¿
@@ -1351,7 +1351,7 @@
 # @else
 #
 # @brief 
-# @param conf
+# @param rtc
 # @param confset_name
 # @param value_name
 # @param ret

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CPUAffinity.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CPUAffinity.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/CPUAffinity.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -130,8 +130,8 @@
     h = ctypes.windll.kernel32.GetCurrentThread()
     
     result = ctypes.windll.kernel32.SetThreadAffinityMask(h, cpu_num)
-    result = ctypes.windll.kernel32.SetThreadAffinityMask(h, cpu_num)
     
+    
     if result != cpu_num:
       return False
     

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ConfigAdmin.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ConfigAdmin.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ConfigAdmin.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -633,7 +633,7 @@
     # update(const char* config_set)
     
     if config_set and config_param is None:
-      if self._configsets.hasKey(config_set) == False:
+      if self._configsets.hasKey(config_set) is None:
         return
       self._changedParam = []
       prop = self._configsets.getNode(config_set)
@@ -803,7 +803,7 @@
   # @endif
   # bool haveConfig(const char* config_id);
   def haveConfig(self, config_id):
-    if self._configsets.hasKey(config_id) == False:
+    if self._configsets.hasKey(config_id) is None:
       return False
     else:
       return True
@@ -1142,7 +1142,7 @@
   # @endif
   # bool activateConfigurationSet(const char* config_id);
   def activateConfigurationSet(self, config_id):
-    if config_id == "":
+    if config_id == "" or config_id is None:
       return False
 
     # '_<conf_name>' is special configuration set name

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/DefaultConfiguration.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/DefaultConfiguration.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/DefaultConfiguration.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -44,7 +44,6 @@
                  "manager.name",                     "manager",
                  "manager.naming_formats",           "%h.host_cxt/%n.mgr",
                  "manager.pid",                      "",
-                 "manager.refstring_path",           "/var/log/rtcmanager.ref",
                  "os.name",                          "",
                  "os.release",                       "",
                  "os.version",                       "",

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Factory.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Factory.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Factory.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -239,7 +239,7 @@
     FactoryBase.__init__(self, profile)
     
     if policy is None:
-      self._policy = OpenRTM_aist.DefaultNumberingPolicy()
+      self._policy = OpenRTM_aist.ProcessUniquePolicy()
     else:
       self._policy = policy
 

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/FactoryInit.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/FactoryInit.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/FactoryInit.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -16,6 +16,7 @@
 #
 
 import OpenRTM_aist
+from OpenRTM_aist.ext.sdo.observer import ComponentObserverConsumer
 
 def FactoryInit():
     # Buffers
@@ -42,7 +43,8 @@
     OpenRTM_aist.InPortSHMConsumerInit()
     OpenRTM_aist.OutPortSHMProviderInit()
     OpenRTM_aist.OutPortSHMConsumerInit()
-    OpenRTM_aist.DefaultNumberingPolicyInit()
+    OpenRTM_aist.ProcessUniquePolicyInit()
     OpenRTM_aist.NodeNumberingPolicyInit()
     OpenRTM_aist.NamingServiceNumberingPolicyInit()
     OpenRTM_aist.LogstreamFileInit()
+    ComponentObserverConsumer.ComponentObserverConsumerInit()

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPort.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPort.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPort.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -109,7 +109,6 @@
 
     self._directNewData = False
     self._valueMutex = threading.RLock()
-    self._outPortConnectorList = []
 
 
   def __del__(self, InPortBase=OpenRTM_aist.InPortBase):
@@ -307,16 +306,8 @@
     del guard
 
 
-    if len(self._outPortConnectorList) > 0:
-      ret, data = self._outPortConnectorList[0].read()
-      
-      if ret:
-        self._value = data
-        if self._OnReadConvert is not None:
-          self._value = self._OnReadConvert(self._value)
-          self._rtcout.RTC_TRACE("OnReadConvert for direct data called")
-        return self._value
 
+
     if len(self._connectors) == 0:
       self._rtcout.RTC_DEBUG("no connectors")
       return self._value
@@ -426,40 +417,5 @@
     self._directNewData = True
     del guard
 
-  ##
-  # @if jp
-  # @brief ¥À¥¤¥ì¥¯¥ÈÄÌ¿®ÍѤÎOutPortPullConnector¤òÄɲÃ
-  # @param self
-  # @param outPortConnector outPortPullConnector
-  # @return OutPort¤Î¥µ¡¼¥Ð¥ó¥È(¼èÆÀ¤Ë¼ºÇÔ¤·¤¿¾ì¹ç¤ÏNone)
-  # @else
-  # @brief Getting local peer InPort if available
-  # @param self
-  # @param profile 
-  # @return 
-  # @endif
-  #
-  # OutPortBase*
-  # setOutPortConnector(const OutPortPullConnector_impl outPortConnector)
-  def addOutPortConnector(self, outPortConnector):
-    self._outPortConnectorList.append(outPortConnector)
-    
 
-
-  ##
-  # @if jp
-  # @brief ¥À¥¤¥ì¥¯¥ÈÄÌ¿®ÍѤÎOutPortPullConnector¤òºï½ü
-  # @param self
-  # @param outPortConnector outPortPullConnector
-  # @else
-  # @brief Getting local peer InPort if available
-  # @param self
-  # @param profile 
-  # @return 
-  # @endif
-  #
-  # OutPortBase*
-  # setOutPortConnector(const OutPortPullConnector_impl outPortConnector)
-  def removeOutPortConnector(self, outPortConnector):
-    self._outPortConnectorList.remove(outPortConnector)
     
\ No newline at end of file

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortBase.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortBase.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortBase.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -1274,6 +1274,18 @@
       elif consumer_ is not None:
         self._rtcout.RTC_TRACE("InPortPullConnector created")
 
+      if OpenRTM_aist.StringUtil.normalize([prop.getProperty("interface_type")]) == "direct":
+        if consumer_ is not None:
+          outport = self.getLocalOutPort(profile)
+
+          if outport is None:
+            self._rtcout.RTC_TRACE("interface_type is direct, ")
+            self._rtcout.RTC_TRACE("but a peer OutPort servant could not be obtained.")
+            del connector
+            return None
+          connector.setOutPort(outport)
+          
+
       # guard = OpenRTM_aist.ScopedLock(self._connector_mutex)
       self._connectors.append(connector)
       self._rtcout.RTC_PARANOID("connector push backed: %d", len(self._connectors))
@@ -1284,3 +1296,35 @@
       return None
 
 
+  ##
+  # @if jp
+  # @brief ¥í¡¼¥«¥ë¤Î¥Ô¥¢OutPort¤ò¼èÆÀ
+  # @param self
+  # @param profile ¥³¥Í¥¯¥¿¥×¥í¥Õ¥¡¥¤¥ë
+  # @return OutPort¤Î¥µ¡¼¥Ð¥ó¥È(¼èÆÀ¤Ë¼ºÇÔ¤·¤¿¾ì¹ç¤ÏNone)
+  # @else
+  # @brief Getting local peer OutPort if available
+  # @param self
+  # @param profile 
+  # @return 
+  # @endif
+  #
+  # OutPortBase*
+  # getLocalOutPort(const ConnectorInfo& profile)
+  def getLocalOutPort(self, profile):
+    self._rtcout.RTC_DEBUG("Trying direct port connection.")
+    orb = OpenRTM_aist.Manager.instance().getORB()
+    self._rtcout.RTC_DEBUG("Current connector profile: name=%s, id=%s" % (profile.name, profile.id))
+    for p in profile.ports:
+      obj = orb.string_to_object(p)
+      if self.getPortRef()._is_equivalent(obj):
+        continue
+      self._rtcout.RTC_DEBUG("Peer port found: %s." % p)
+      try:
+        poa = OpenRTM_aist.Manager.instance().getPOA()
+        outport = poa.reference_to_servant(obj)
+        self._rtcout.RTC_DEBUG("OutPortBase servant pointer is obtained.")
+        return outport
+      except:
+        self._rtcout.RTC_DEBUG("Peer port might be a remote port")
+    return None

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPullConnector.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPullConnector.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPullConnector.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -124,16 +124,18 @@
   #                     OutPortConsumer* consumer,
   #                     ConnectorListeners& listeners,
   #                     CdrBufferBase* buffer = 0);
-  def __init__(self, info, consumer, listeners, buffer = 0):
+  def __init__(self, info, consumer, listeners, buffer = None):
     OpenRTM_aist.InPortConnector.__init__(self, info, buffer)
     self._consumer = consumer
     self._listeners = listeners
+    self._directOutPort = None
+    self._outPortListeners = None
 
 
-    if buffer == 0:
+    if buffer is None:
       self._buffer = self.createBuffer(self._profile)
 
-    if self._buffer == 0 or not self._consumer:
+    if not self._buffer or not self._consumer:
       raise
         
     self._buffer.init(info.properties.getNode("buffer"))
@@ -197,6 +199,32 @@
   # virtual ReturnCode read(cdrMemoryStream& data);
   def read(self, data):
     self._rtcout.RTC_TRACE("InPortPullConnector.read()")
+
+    if self._directOutPort is not None:
+      if self._directOutPort.isEmpty():
+        self._listeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_BUFFER_EMPTY].notify(self._profile)
+        self._outPortListeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_SENDER_EMPTY].notify(self._profile)
+        self._rtcout.RTC_TRACE("ON_BUFFER_EMPTY(InPort,OutPort), ")
+        self._rtcout.RTC_TRACE("ON_SENDER_EMPTY(InPort,OutPort) ")
+        self._rtcout.RTC_TRACE("callback called in direct mode.")
+
+      self._directOutPort.read(data)
+      #self._outPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_READ].notify(self._profile, data[0])
+      self._rtcout.RTC_TRACE("ON_BUFFER_READ(OutPort), ")
+      self._rtcout.RTC_TRACE("callback called in direct mode.")
+      #self._outPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_SEND].notify(self._profile, data[0])
+      self._rtcout.RTC_TRACE("ON_SEND(OutPort), ")
+      self._rtcout.RTC_TRACE("callback called in direct mode.")
+      #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data[0])
+      self._rtcout.RTC_TRACE("ON_RECEIVED(InPort), ")
+      self._rtcout.RTC_TRACE("callback called in direct mode.")
+      #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_SEND].notify(self._profile, data[0])
+      self._rtcout.RTC_TRACE("ON_BUFFER_WRITE(InPort), ")
+      self._rtcout.RTC_TRACE("callback called in direct mode.")
+      return self.PORT_OK
+
+
+
     if not self._consumer:
       return self.PORT_ERROR
 
@@ -325,6 +353,29 @@
       self._listeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_DISCONNECT].notify(self._profile)
     return
 
-  
 
 
+  ##
+  # @if jp
+  # @brief ¥Ç¡¼¥¿¤ò¥À¥¤¥ì¥¯¥È¤Ë½ñ¤­¹þ¤à¤¿¤á¤ÎOutPort¤Î¥µ¡¼¥Ð¥ó¥È¤òÀßÄꤹ¤ë
+  #
+  # @param self
+  # @param directOutPort OutPort¤Î¥µ¡¼¥Ð¥ó¥È
+  # @return True: ÀßÄê¤ËÀ®¸ù False: ´û¤ËÀßÄêºÑ¤ß¤Î¤¿¤á¼ºÇÔ
+  # @else
+  # @brief 
+  #
+  # @param self
+  # @param directOutPort 
+  # @return 
+  # @endif
+  #
+  # bool setOutPort(setOutPort* directOutPort);
+  def setOutPort(self, directOutPort):
+    if self._directOutPort is not None:
+      return False
+    self._directOutPort = directOutPort
+    self._outPortListeners = self._directOutPort._listeners
+    return True
+
+

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPushConnector.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPushConnector.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/InPortPushConnector.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -119,7 +119,7 @@
   #
   # InPortPushConnector(ConnectorInfo info, InPortProvider* provider,
   #                    ConnectorListeners listeners, CdrBufferBase* buffer = 0);
-  def __init__(self, info, provider, listeners, buffer = 0):
+  def __init__(self, info, provider, listeners, buffer = None):
     OpenRTM_aist.InPortConnector.__init__(self, info, buffer)
     self._provider = provider
     self._listeners = listeners

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Manager.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Manager.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Manager.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -450,10 +450,8 @@
     for i in range(len(mods)):
       if mods[i] is None or mods[i] == "":
         continue
-      tmp = [mods[i]]
-      OpenRTM_aist.eraseHeadBlank(tmp)
-      OpenRTM_aist.eraseTailBlank(tmp)
-      mods[i] = tmp[0]
+      mods[i] = mods[i].strip()
+      
 
       basename = os.path.basename(mods[i]).split(".")[0]
       basename += "Init"
@@ -467,9 +465,9 @@
     sdofactory_ = OpenRTM_aist.SdoServiceConsumerFactory.instance()
     self._config.setProperty("sdo.service.consumer.available_services",
                              OpenRTM_aist.flatten(sdofactory_.getIdentifiers()))
-    if self._initProc:
-      self._initProc(self)
 
+
+    self.invokeInitProc()
     self.initPreCreation()
     
     self.initPreConnection()
@@ -987,9 +985,9 @@
     prop_ = prop.getNode("port")
     prop_.mergeProperties(self._config.getNode("port"))
 
+
     comp = factory.create(self)
-    if self._config.getProperty("corba.endpoints_ipv4") == "":
-      self.setEndpointProperty(comp.getObjRef())
+    
 
     for i in range(len(inherit_prop)):
       if self._config.findNode(inherit_prop[i]):
@@ -999,6 +997,10 @@
       self._rtcout.RTC_ERROR("createComponent: RTC creation failed: %s",
                              comp_id.getProperty("implementation_id"))
       return None
+
+    if self._config.getProperty("corba.endpoints_ipv4") == "":
+      self.setEndpointProperty(comp.getObjRef())
+      
     self._rtcout.RTC_TRACE("RTC Created: %s", comp_id.getProperty("implementation_id"))
     self._listeners.rtclifecycle_.postCreate(comp)
 
@@ -1032,6 +1034,7 @@
       if comp.exit() != RTC.RTC_OK:
         self._rtcout.RTC_DEBUG("%s finalization was failed.",
                                comp_id.getProperty("implementation_id"))
+      comp.exit()
       return None
       
     self._rtcout.RTC_TRACE("RTC initialization succeeded: %s",
@@ -1452,10 +1455,6 @@
 
     lmpm_ = [s.strip() for s in self._config.getProperty("manager.preload.modules").split(",")]
     for mpm_ in lmpm_:
-      tmp = [mpm_]
-      OpenRTM_aist.eraseHeadBlank(tmp)
-      OpenRTM_aist.eraseTailBlank(tmp)
-      mpm_ = tmp[0]
       if len(mpm_) == 0:
         continue
       basename_ = mpm_.split(".")[0]+"Init"
@@ -1730,7 +1729,15 @@
   def initORB(self):
     self._rtcout.RTC_TRACE("Manager.initORB()")
     try:
-      args = OpenRTM_aist.split(self.createORBOptions(), " ")
+      tmp_args = self.createORBOptions().split("\"")
+      args = []
+      for i in range(len(tmp_args)):
+        if i%2 == 0:
+          args.extend(tmp_args[i].split(" "))
+        else:
+          args.append(tmp_args[i])
+        
+      
       args.insert(0,"manager")
       argv = OpenRTM_aist.toArgv(args)
       
@@ -2317,26 +2324,14 @@
           tm.set_time(duration)
         if self._timer:
           self._timer.registerListenerObj(self._mgrservant,
-                                        OpenRTM_aist.ManagerServant.update_master_manager,
+                                        OpenRTM_aist.ManagerServant.updateMasterManager,
                                         tm)
 
     otherref = None
 
-    try:
-      otherref = open(self._config.getProperty("manager.refstring_path"),'r')
-      #refstring = otherref.readline()
-      otherref.close()
-    except:
-      try:
-        reffile = open(self._config.getProperty("manager.refstring_path"),'w')
-      except:
-        self._rtcout.RTC_WARN(OpenRTM_aist.Logger.print_exception())
-        return False
-      else:
-        reffile.write(self._orb.object_to_string(self._mgrservant.getObjRef()))
-        reffile.close()
 
 
+
     return True
 
   
@@ -3070,7 +3065,7 @@
   # @if jp
   # @brief µ¯Æ°»þ¤Ërtc.conf¤Ç»ØÄꤷ¤¿¥Ý¡¼¥È¤òÀܳ¤¹¤ë
   # Îã:
-  # manager.components.preconnect: RTC0.port0:RTC0.port1(interface_type=corba_cdr&dataflow_type=pull&~),~
+  # manager.components.preconnect: RTC0.port0?port=RTC0.port1&interface_type=corba_cdr&dataflow_type=pull&~,~
   # @param self
   # @else
   #
@@ -3083,26 +3078,47 @@
     connectors = str(self._config.getProperty("manager.components.preconnect")).split(",")
     
     for c in connectors:
-      tmp = [c]
-      OpenRTM_aist.eraseHeadBlank(tmp)
-      OpenRTM_aist.eraseTailBlank(tmp)
-      c = tmp[0]
+      c = c.strip()
       if len(c) == 0:
         continue
-      conn_prop = c.split("(")
-      if len(conn_prop) < 2:
+      port0_str = c.split("?")[0]
+      param = OpenRTM_aist.urlparam2map(c)
+      
+
+
+      ports = []
+      configs = {}
+      for k,p in param.items():
+        if k == "port":
+          ports.append(p)
+          continue
+        tmp = k.replace("port","")
+        v = [0]
+        if OpenRTM_aist.stringTo(v, tmp):
+          ports.append(p)
+          continue
+        configs[k] = p
+
+      if len(ports) == 0:
         self._rtcout.RTC_ERROR("Invalid format for pre-connection.")
+        self._rtcout.RTC_ERROR("Format must be Comp0.port0?port=Comp1.port1")
         continue
-      conn_prop[1] = conn_prop[1].replace(")","")
-      comp_ports = conn_prop[0].split(":")
-      if len(comp_ports) != 2:
-        self._rtcout.RTC_ERROR("Invalid format for pre-connection.")
-        self._rtcout.RTC_ERROR("Format must be Comp0.port0:Comp1.port1()")
-        continue
+    
+      if not ("dataflow_type" in configs.keys()):
+        configs["dataflow_type"] = "push"
+      if not ("interface_type" in configs.keys()):
+        configs["interface_type"] = "corba_cdr"
       
-      comp0_name = comp_ports[0].split(".")[0]
-      port0_name = comp_ports[0]
       
+      
+      tmp = port0_str.split(".")
+      tmp.pop()
+      comp0_name = OpenRTM_aist.flatten(tmp,".")
+      
+
+      port0_name = port0_str
+      
+      
       if comp0_name.find("://") == -1:
         comp0 = self.getComponent(comp0_name)
         if comp0 is None:
@@ -3116,61 +3132,57 @@
           self._rtcout.RTC_ERROR("%s not found." % comp0_name)
           continue
         comp0_ref = rtcs[0]
-        port0_name = comp_ports[0].split("/")[-1]
+        port0_name = port0_str.split("/")[-1]
       
-        
       
       port0_var = OpenRTM_aist.CORBA_RTCUtil.get_port_by_name(comp0_ref, port0_name)
       
+      
       if CORBA.is_nil(port0_var):
-        self._rtcout.RTC_DEBUG("port %s found: " % comp_ports[0])
+        self._rtcout.RTC_DEBUG("port %s found: " % port0_str)
         continue
 
-      comp1_name = comp_ports[1].split(".")[0]
-      port1_name = comp_ports[1]
+      for port_str in ports:
       
+        tmp = port_str.split(".")
+        tmp.pop()
+        comp_name = OpenRTM_aist.flatten(tmp,".")
+        port_name = port_str
       
+      
 
 
-      if comp1_name.find("://") == -1:
-        comp1 = self.getComponent(comp1_name)
-        if comp1 is None:
-          self._rtcout.RTC_ERROR("%s not found." % comp1_name)
-          continue
-        comp1_ref = comp1.getObjRef()
-      else:
-        rtcs = self._namingManager.string_to_component(comp1_name)
-        
-        if len(rtcs) == 0:
-          self._rtcout.RTC_ERROR("%s not found." % comp1_name)
-          continue
-        comp1_ref = rtcs[0]
-        port1_name = comp_ports[1].split("/")[-1]
+        if comp_name.find("://") == -1:
+          comp = self.getComponent(comp_name)
+          if comp is None:
+            self._rtcout.RTC_ERROR("%s not found." % comp_name)
+            continue
+          comp_ref = comp.getObjRef()
+        else:
+          rtcs = self._namingManager.string_to_component(comp_name)
+          
+          if len(rtcs) == 0:
+            self._rtcout.RTC_ERROR("%s not found." % comp_name)
+            continue
+          comp_ref = rtcs[0]
+          port_name = port_str.split("/")[-1]
+  
 
-
-      port1_var = OpenRTM_aist.CORBA_RTCUtil.get_port_by_name(comp1_ref, port1_name)
+        port_var = OpenRTM_aist.CORBA_RTCUtil.get_port_by_name(comp_ref, port_name)
       
-      if CORBA.is_nil(port1_var):
-        self._rtcout.RTC_DEBUG("port %s found: " % comp_ports[1])
-        continue
+        if CORBA.is_nil(port_var):
+          self._rtcout.RTC_DEBUG("port %s found: " % port_str)
+          continue
       
-      prop = OpenRTM_aist.Properties()
-      opt_props = conn_prop[1].split("&")
-      for o in opt_props:
-        temp = o.split("=")
-        if len(temp) == 2:
-          s = [temp[0]]
-          OpenRTM_aist.eraseHeadBlank(s)
-          OpenRTM_aist.eraseTailBlank(s)
-          temp[0] = s[0]
-          s = [temp[1]]
-          OpenRTM_aist.eraseHeadBlank(s)
-          OpenRTM_aist.eraseTailBlank(s)
-          temp[1] = s[0]
-          prop.setProperty("dataport."+temp[0],temp[1])
+        prop = OpenRTM_aist.Properties()
+        
+        for k,v in configs.items():
+          k = k.strip()
+          v = v.strip()
+          prop.setProperty("dataport."+k,v)
       
-      if RTC.RTC_OK != OpenRTM_aist.CORBA_RTCUtil.connect(c, prop, port0_var, port1_var):
-        self._rtcout.RTC_ERROR("Connection error: %s" % c)
+        if RTC.RTC_OK != OpenRTM_aist.CORBA_RTCUtil.connect(c, prop, port0_var, port_var):
+          self._rtcout.RTC_ERROR("Connection error: %s" % c)
       
 
 
@@ -3192,11 +3204,9 @@
     self._rtcout.RTC_TRACE("Components pre-activation: %s" % str(self._config.getProperty("manager.components.preactivation")))
     comps = str(self._config.getProperty("manager.components.preactivation")).split(",")
     for c in comps:
-      tmp = [c]
-      OpenRTM_aist.eraseHeadBlank(tmp)
-      OpenRTM_aist.eraseTailBlank(tmp)
-      c = tmp[0]
+      c = c.strip()
       if c:
+        comp_ref = None
         if c.find("://") == -1:
           comp = self.getComponent(c)
           if comp is None:
@@ -3233,12 +3243,23 @@
     for i in range(len(comps)):
       if comps[i] is None or comps[i] == "":
         continue
-      tmp = [comps[i]]
-      OpenRTM_aist.eraseHeadBlank(tmp)
-      OpenRTM_aist.eraseTailBlank(tmp)
-      comps[i] = tmp[0]
+      comps[i] = comps[i].strip()
 
       self.createComponent(comps[i])
+
+
+  ##
+  # @if jp
+  # @brief 
+  # @else
+  #
+  # @brief 
+  # @param self
+  # @endif
+  # void initPreCreation()
+  def invokeInitProc(self):
+    if self._initProc:
+      self._initProc(self)
     
   ##
   # @if jp

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerConfig.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerConfig.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerConfig.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -81,7 +81,6 @@
 class ManagerConfig :
   """
   """
-
   ##
   # @if jp
   # @brief Manager ¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó¤Î¥Ç¥Õ¥©¥ë¥È¡¦¥Õ¥¡¥¤¥ë¡¦¥Ñ¥¹
@@ -88,14 +87,21 @@
   # @else
   # @brief The default configuration file path for manager
   # @endif
-  config_file_path = ["./rtc.conf",
-                      "/etc/rtc.conf",
-                      "/etc/rtc/rtc.conf",
-                      "/usr/local/etc/rtc.conf",
-                      "/usr/local/etc/rtc/rtc.conf",
-                      None]
+  if sys.platform == 'win32':
 
+    config_file_path = ["./rtc.conf",
+                        "${RTM_ROOT}bin/${RTM_VC_VERSION}/rtc.conf",
+                        "C:/Python"+str(sys.version_info[0])+str(sys.version_info[1])+"/rtc.conf",
+                        None]
+  else:
+    config_file_path = ["./rtc.conf",
+                        "/etc/rtc.conf",
+                        "/etc/rtc/rtc.conf",
+                        "/usr/local/etc/rtc.conf",
+                        "/usr/local/etc/rtc/rtc.conf",
+                        None]
 
+
   ##
   # @if jp
   # @brief ¥Ç¥Õ¥©¥ë¥È¡¦¥³¥ó¥Õ¥£¥®¥å¥ì¡¼¥·¥ç¥ó¤Î¥Õ¥¡¥¤¥ë¡¦¥Ñ¥¹¤ò¼±Ê̤¹¤ë
@@ -339,6 +345,7 @@
 
     i = 0
     while (self.config_file_path[i]):
+      self.config_file_path[i] = OpenRTM_aist.replaceEnv(self.config_file_path[i])
       if self.fileExist(self.config_file_path[i]):
         self._configFile = self.config_file_path[i]
         return True

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerServant.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerServant.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ManagerServant.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -481,11 +481,11 @@
     self._rtcout.RTC_TRACE("create_component(%s)", module_name)
 
     
-    rtc = self.create_component_by_address(module_name)
+    rtc = self.createComponentByAddress(module_name)
     if not CORBA.is_nil(rtc):
       return rtc
     
-    rtc = self.create_component_by_mgrname(module_name)
+    rtc = self.createComponentByManagerName(module_name)
     
     if not CORBA.is_nil(rtc):
       return rtc
@@ -494,8 +494,8 @@
 
     #module_name = module_name.split("&")[0]
     module_name = [module_name]
-    self.get_parameter_by_modulename("manager_address",module_name)
-    manager_name = self.get_parameter_by_modulename("manager_name",module_name)
+    self.getParameterByModulename("manager_address",module_name)
+    manager_name = self.getParameterByModulename("manager_name",module_name)
     module_name = module_name[0]
 
     comp_param = CompParam(module_name)
@@ -522,7 +522,7 @@
       if not manager_name:
         module_name = module_name + "&manager_name=manager_%p"
         
-        rtc = self.create_component_by_mgrname(module_name)
+        rtc = self.createComponentByManagerName(module_name)
         return rtc
 
     else:
@@ -1178,9 +1178,9 @@
   # @param manager_name
   # @return 
   # @endif
-  # RTC::Manager_ptr findManager_by_name(string manager_name)
-  def findManager_by_name(self, manager_name):
-    self._rtcout.RTC_TRACE("findManager_by_name(manager_name = %s)", manager_name)
+  # RTC::Manager_ptr findManagerByName(string manager_name)
+  def findManagerByName(self, manager_name):
+    self._rtcout.RTC_TRACE("findManagerByName(manager_name = %s)", manager_name)
     prop = self._mgr.getConfig()
     name = prop.getProperty("manager.instance_name")
     if name == manager_name:
@@ -1252,8 +1252,8 @@
   # @param module_name
   # @return 
   # @endif
-  # std::string get_parameter_by_modulename(string param_name, string &module_name)
-  def get_parameter_by_modulename(self, param_name, module_name):
+  # std::string getParameterByModulename(string param_name, string &module_name)
+  def getParameterByModulename(self, param_name, module_name):
     arg = module_name[0]
     pos0 = arg.find("&"+param_name+"=")
     pos1 = arg.find("?"+param_name+"=")
@@ -1263,11 +1263,13 @@
     if pos0 == -1 and pos1 == -1:
       return ""
 
+    pos = 0
     if pos0 == -1:
       pos = pos1
     else:
       pos = pos0
 
+    paramstr = ""
     endpos = arg.find('&', pos + 1)
     if endpos == -1:
       endpos = arg.find('?', pos + 1)
@@ -1316,14 +1318,14 @@
   # @param module_name
   # @return 
   # @endif
-  # RTC::RTObject_ptr create_component_by_mgrname(string module_name)
-  def create_component_by_mgrname(self, module_name):
+  # RTC::RTObject_ptr createComponentByManagerName(string module_name)
+  def createComponentByManagerName(self, module_name):
     
     arg = module_name
     
 
     tmp = [arg]
-    mgrstr = self.get_parameter_by_modulename("manager_name",tmp)
+    mgrstr = self.getParameterByModulename("manager_name",tmp)
     arg = tmp[0]
 
     if not mgrstr:
@@ -1333,7 +1335,7 @@
     if mgrstr == "manager_%p":
       mgrobj = RTM.Manager._nil
     else:
-      mgrobj = self.findManager_by_name(mgrstr)
+      mgrobj = self.findManagerByName(mgrstr)
     
 
 
@@ -1373,16 +1375,7 @@
       
       
       self._rtcout.RTC_DEBUG("Invoking command: %s.", cmd)
-      
-      ret = OpenRTM_aist.launch_shell(cmd)
 
-      
-      if ret == -1:
-        self._rtcout.RTC_DEBUG("%s: failed", cmd)
-        return RTC.RTObject._nil
-      time.sleep(0.01)
-      count = 0
-      
       slaves_names = []
       regex = r'manager_[0-9]+'
       if mgrstr == "manager_%p":
@@ -1402,6 +1395,19 @@
             
         del guard_slave
 
+
+
+      ret = OpenRTM_aist.launch_shell(cmd)
+
+      
+      if ret == -1:
+        self._rtcout.RTC_DEBUG("%s: failed", cmd)
+        return RTC.RTObject._nil
+      time.sleep(0.01)
+      count = 0
+      
+
+
       t0_ = OpenRTM_aist.Time()
       
       while CORBA.is_nil(mgrobj):
@@ -1425,7 +1431,7 @@
           del guard_slave
           
         else:
-          mgrobj = self.findManager_by_name(mgrstr)
+          mgrobj = self.findManagerByName(mgrstr)
         count += 1
         if count > 1000:
           break
@@ -1482,12 +1488,12 @@
   # @param module_name
   # @return 
   # @endif
-  # RTC::RTObject_ptr create_component_by_address(string module_name)
-  def create_component_by_address(self, module_name):
+  # RTC::RTObject_ptr createComponentByAddress(string module_name)
+  def createComponentByAddress(self, module_name):
 
     arg = module_name
     tmp = [arg]
-    mgrstr = self.get_parameter_by_modulename("manager_address",tmp)
+    mgrstr = self.getParameterByModulename("manager_address",tmp)
     arg = tmp[0]
 
     if not mgrstr:
@@ -1495,7 +1501,7 @@
     
     mgrvstr = mgrstr.split(":")
     if len(mgrvstr) != 2:
-      self._rtcout.RTC_WARN("Invalid manager name: %s", mgrstr)
+      self._rtcout.RTC_WARN("Invalid manager address: %s", mgrstr)
       return RTC.RTObject._nil
 
     
@@ -1579,8 +1585,8 @@
   # @brief 
   # @param self
   # @endif
-  # void update_master_manager()
-  def update_master_manager(self):
+  # void updateMasterManager()
+  def updateMasterManager(self):
     if not self._isMaster and self._objref:
       guard = OpenRTM_aist.ScopedLock(self._masterMutex)
       if len(self._masters) > 0:

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ModuleManager.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ModuleManager.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ModuleManager.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -282,6 +282,13 @@
     if not self.fileExist(file_path):
       raise ModuleManager.FileNotFound(file_name)
 
+    
+    with open(str(file_path)) as f:
+      if init_func is not None:
+        if f.read().find(init_func) == -1:
+          raise ModuleManager.FileNotFound(file_name)
+          
+
     if not pathChanged:
       splitted_name = os.path.split(file_path)
       sys.path.append(splitted_name[0])
@@ -474,7 +481,13 @@
     # for new
     comp_spec_name = classname+"_spec"
 
+
+    
+        
     try:
+      with open(str(fullname)) as f:
+        if f.read().find(comp_spec_name) == -1:
+          return None
       imp_file = __import__(basename.split(".")[0])
     except:
       return None

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingManager.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingManager.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingManager.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -256,7 +256,11 @@
     self._rtcout.RTC_TRACE("isAlive()")
     return self._cosnaming.isAlive()
 
+  def getCorbaNaming(self):
+    self._rtcout.RTC_TRACE("getCorbaNaming()")
+    return self._cosnaming
 
+
   ##
   # @if jp
   #
@@ -275,13 +279,13 @@
   # @else
   #
   # @endif
-  def get_RTC_by_Name(self, context, name, rtcs):
+  def getComponentByName(self, context, name, rtcs):
     length = 500
     bl,bi = context.list(length)
     for i in bl:
       if i.binding_type == CosNaming.ncontext:
         next_context = context.resolve(i.binding_name)
-        self.get_RTC_by_Name(next_context, name, rtcs)
+        self.getComponentByName(next_context, name, rtcs)
       elif i.binding_type == CosNaming.nobject:
         
         if i.binding_name[0].id == name and i.binding_name[0].kind == "rtc":
@@ -289,7 +293,8 @@
             cc = OpenRTM_aist.CorbaConsumer()
             cc.setObject(context.resolve(i.binding_name))
             obj = cc.getObject()._narrow(RTC.RTObject)
-            rtcs.append(obj)
+            if not obj._non_existent():
+              rtcs.append(obj)
           except:
             self._rtcout.RTC_ERROR(OpenRTM_aist.Logger.print_exception())
     
@@ -325,6 +330,7 @@
           rtc_name = url[len(host)+1:]
           
           try:
+            cns = None
             if host == "*":
               cns = self._cosnaming
             else:
@@ -334,7 +340,7 @@
             
             if len(names) == 2 and names[0] == "*":
               root_cxt = cns.getRootContext()
-              self.get_RTC_by_Name(root_cxt, names[1], rtc_list)
+              self.getComponentByName(root_cxt, names[1], rtc_list)
               return rtc_list
             else:
               rtc_name += ".rtc"
@@ -341,6 +347,8 @@
               obj = cns.resolveStr(rtc_name)
               if CORBA.is_nil(obj):
                 return []
+              if obj._non_existent():
+                return []
               rtc_list.append(obj)
               return rtc_list
           except:
@@ -379,10 +387,14 @@
   #
   # @param self
   # @param orb ORB
-  # @param names NamingServer ̾¾Î
+  # @param mgr ¥Þ¥Í¡¼¥¸¥ã
   #
   # @else
   #
+  # @param self
+  # @param orb ORB
+  # @param mgr 
+  #
   # @endif
   def __init__(self, orb, mgr):
     self._rtcout = OpenRTM_aist.Manager.instance().getLogbuf('manager.namingonmanager')
@@ -478,7 +490,7 @@
   #
   # @param name rtcloc·Á¼°¤Ç¤ÎRTC̾
   # rtcloc://localhost:2809/example/ConsoleIn
-  # @return RTC¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹
+  # @return RTC¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹¤Î¥ê¥¹¥È
   #
   # @else
   #
@@ -503,7 +515,7 @@
           rtc_name = url[len(host)+1:]
           
           mgr = self.getManager(host)
-          if mgr:
+          if not CORBA.is_nil(mgr):
             rtc_list = mgr.get_components_by_name(rtc_name)
 
             slaves = mgr.get_slave_managers()
@@ -521,6 +533,8 @@
   # @if jp
   #
   # @brief »ØÄê¥Û¥¹¥È̾¡¢¥Ý¡¼¥È̾¤ÇManager¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹¤ò¼èÆÀ
+  #
+  # @param name ¥Û¥¹¥È̾¡¢¥Ý¡¼¥È̾
   # 
   # @return Manager¤Î¥ª¥Ö¥¸¥§¥¯¥È¥ê¥Õ¥¡¥ì¥ó¥¹
   #
@@ -536,6 +550,7 @@
   def getManager(self, name):
     if name == "*":
       mgr_sev = self._mgr.getManagerServant()
+      mgr = None
       if mgr_sev.is_master():
         mgr = mgr_sev.getObjRef()
       else:

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingServiceNumberingPolicy.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingServiceNumberingPolicy.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NamingServiceNumberingPolicy.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -77,6 +77,7 @@
         return num_str
       else:
         num += 1
+    return OpenRTM_aist.otos(num)
 
   ##
   # @if jp

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NodeNumberingPolicy.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NodeNumberingPolicy.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NodeNumberingPolicy.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -74,6 +74,7 @@
         return num_str
       else:
         num += 1
+    return OpenRTM_aist.otos(num)
         
 
   ##

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NumberingPolicy.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NumberingPolicy.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/NumberingPolicy.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -95,7 +95,7 @@
 ##
 # @if jp
 #
-# @class DefaultNumberingPolicy
+# @class ProcessUniquePolicy
 # @brief ¥ª¥Ö¥¸¥§¥¯¥ÈÀ¸À®»þ¥Í¡¼¥ß¥ó¥°¡¦¥Ý¥ê¥·¡¼(̿̾µ¬Â§)´ÉÍýÍÑ¥¯¥é¥¹
 #
 # ¥ª¥Ö¥¸¥§¥¯¥È¤òÀ¸À®¤¹¤ëºÝ¤Î¥Í¡¼¥ß¥ó¥°¡¦¥Ý¥ê¥·¡¼(̿̾µ¬Â§)¤ò´ÉÍý¤¹¤ë¤¿¤á¤Î
@@ -106,7 +106,7 @@
 # @else
 #
 # @endif
-class DefaultNumberingPolicy(NumberingPolicy):
+class ProcessUniquePolicy(NumberingPolicy):
   """
   """
 
@@ -209,8 +209,11 @@
     raise NumberingPolicy.ObjectNotFound()
 
 
-def DefaultNumberingPolicyInit():
+def ProcessUniquePolicyInit():
+  OpenRTM_aist.NumberingPolicyFactory.instance().addFactory("default",
+                                                      OpenRTM_aist.ProcessUniquePolicy,
+                                                      OpenRTM_aist.Delete)
   OpenRTM_aist.NumberingPolicyFactory.instance().addFactory("process_unique",
-                                                      OpenRTM_aist.DefaultNumberingPolicy,
+                                                      OpenRTM_aist.ProcessUniquePolicy,
                                                       OpenRTM_aist.Delete)
 

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPort.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPort.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPort.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -21,6 +21,7 @@
 from omniORB import any
 
 import OpenRTM_aist
+import threading
 
 
 ##
@@ -101,7 +102,11 @@
     #self._OnUnderflow    = None
     #self._OnConnect      = None
     #self._OnDisconnect   = None
+    self._directNewData = False
+    self._valueMutex = threading.RLock()
+    self._directValue = value
     
+    
 
   def __del__(self, OutPortBase=OpenRTM_aist.OutPortBase):
     OutPortBase.__del__(self)
@@ -178,11 +183,17 @@
 
     guard = OpenRTM_aist.ScopedLock(self._connector_mutex)
     for con in self._connectors:
-      ret = con.write(value)
-      if ret != self.PORT_OK:
-        result = False
-        if ret == self.CONNECTION_LOST:
-          self.disconnect(con.id())
+      if not con.directMode():
+        ret = con.write(value)
+        if ret != self.PORT_OK:
+          result = False
+          if ret == self.CONNECTION_LOST:
+            self.disconnect(con.id())
+      else:
+        guard = OpenRTM_aist.ScopedLock(self._valueMutex)
+        self._directValue = value
+        self._directNewData = True
+    del guard
 
     return result
 
@@ -288,7 +299,33 @@
     return str(val.typecode().name())
 
 
+  ##
+  # @if jp
+  #
+  # @brief ¥Ç¡¼¥¿¤ò¥À¥¤¥ì¥¯¥È¤ËÆɤ߹þ¤à
+  #
+  # @param self
+  # @param data Æɤ߹þ¤à¥Ç¡¼¥¿
+  #
+  # @else
+  # @brief 
+  #
+  # @param self
+  # @param data 
+  # @endif
+  # void read(const DataType& data)
+  def read(self, data):
+    guard = OpenRTM_aist.ScopedLock(self._valueMutex)
+    self._directNewData = False
+    data[0] = self._directValue
+    if self._OnWriteConvert:
+      data[0] = self._OnWriteConvert(data[0])
+    del guard
+  def isEmpty(self):
+    return (not self._directNewData)
+    
 
+
   class subscribe:
     def __init__(self, prof, subs = None):
       if subs:

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortBase.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortBase.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortBase.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -579,7 +579,7 @@
         return self._connectors[i]
 
     self._rtcout.RTC_WARN("ConnectorProfile with the id(%s) not found.", id)
-    return 0
+    return None
 
   ##
   # @if jp
@@ -610,7 +610,7 @@
         return self._connectors[i]
 
     self._rtcout.RTC_WARN("ConnectorProfile with the name(%s) not found.", name)
-    return 0
+    return None
 
 
   ##
@@ -1193,7 +1193,7 @@
       self._rtcout.RTC_DEBUG("interface_type:  %s", prop.getProperty("interface_type"))
       self._rtcout.RTC_DEBUG("interface_types: %s",
                              OpenRTM_aist.flatten(self._providerTypes))
-      return 0
+      return None
 
     self._rtcout.RTC_DEBUG("interface_type: %s", prop.getProperty("interface_type"))
     provider = OpenRTM_aist.OutPortProviderFactory.instance().createObject(prop.getProperty("interface_type"))
@@ -1205,12 +1205,12 @@
       if not provider.publishInterface(cprof.properties):
         self._rtcout.RTC_ERROR("publishing interface information error")
         OpenRTM_aist.OutPortProviderFactory.instance().deleteObject(provider)
-        return 0
+        return None
 
       return provider
 
     self._rtcout.RTC_ERROR("provider creation failed")
-    return 0
+    return None
 
 
   ##
@@ -1229,7 +1229,7 @@
       self._rtcout.RTC_DEBUG("interface_type:  %s", prop.getProperty("interface_type"))
       self._rtcout.RTC_DEBUG("interface_types: %s",
                              OpenRTM_aist.flatten(self._consumerTypes))
-      return 0
+      return None
     
     self._rtcout.RTC_DEBUG("interface_type: %s", prop.getProperty("interface_type"))
     consumer = OpenRTM_aist.InPortConsumerFactory.instance().createObject(prop.getProperty("interface_type"))
@@ -1247,7 +1247,7 @@
       return consumer
 
     self._rtcout.RTC_ERROR("consumer creation failed")
-    return 0
+    return None
 
 
   ##
@@ -1277,7 +1277,7 @@
 
       else:
         self._rtcout.RTC_ERROR("provider or consumer is not passed. returned 0;")
-        return 0
+        return None
 
       #if connector is None:
       #  self._rtcout.RTC_ERROR("OutPortConnector creation failed")
@@ -1290,20 +1290,23 @@
 
         
       if OpenRTM_aist.StringUtil.normalize([prop.getProperty("interface_type")]) == "direct":
+        if consumer_ is not None:
+          inport = self.getLocalInPort(profile)
         
-        inport = self.getLocalInPort(profile)
-        
-        if inport is None:
-          self._rtcout.RTC_TRACE("interface_type is direct, ")
-          self._rtcout.RTC_TRACE("but a peer InPort servant could not be obtained.")
-          del connector
-          return 0
+          if inport is None:
+            self._rtcout.RTC_TRACE("interface_type is direct, ")
+            self._rtcout.RTC_TRACE("but a peer InPort servant could not be obtained.")
+            del connector
+            return None
 
-        connector.setInPort(inport)
+          connector.setInPort(inport)
         #if consumer_ is not None:
         #  connector.setInPort(inport)
         #elif provider_ is not None:
         #  connector.setInPort(inport)
+        else:
+          connector.setDirectMode()
+          
 
 
       self._connectors.append(connector)
@@ -1313,7 +1316,7 @@
     except:
       self._rtcout.RTC_ERROR("Exeption: OutPortPushConnector creation failed")
       self._rtcout.RTC_ERROR(OpenRTM_aist.Logger.print_exception())
-      return 0
+      return None
 
 
 

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortConnector.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortConnector.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortConnector.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -57,6 +57,7 @@
     self._rtcout = OpenRTM_aist.Manager.instance().getLogbuf("OutPortConnector")
     self._profile = info
     self._endian = True
+    self._directMode = False
     return
 
   ##
@@ -150,3 +151,36 @@
       self._endian = True # little endian
 
     return RTC.RTC_OK
+
+  ##
+  # @if jp
+  # @brief ¥À¥¤¥ì¥¯¥ÈÀܳ¥â¡¼¥É¤ËÀßÄê
+  #
+  #
+  # @else
+  # @brief 
+  #
+  # This 
+  #
+  # @endif
+  #
+  # const char* name();
+  def setDirectMode(self):
+    self._directMode = True
+
+  ##
+  # @if jp
+  # @brief ¥À¥¤¥ì¥¯¥ÈÀܳ¥â¡¼¥É¤«¤ÎȽÄê
+  #
+  # @return True¡§¥À¥¤¥ì¥¯¥ÈÀܳ¥â¡¼¥É,false¡§¤½¤ì°Ê³°
+  #
+  # @else
+  # @brief 
+  #
+  # @return
+  #
+  # @endif
+  #
+  # const char* name();
+  def directMode(self):
+    return self._directMode

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPullConnector.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPullConnector.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPullConnector.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -123,18 +123,14 @@
   #                      OutPortProvider* provider,
   #                      ConnectorListeners& listeners,
   #                      CdrBufferBase* buffer = 0);
-  def __init__(self, info, provider, listeners, buffer = 0):
+  def __init__(self, info, provider, listeners, buffer = None):
     OpenRTM_aist.OutPortConnector.__init__(self, info)
     self._provider = provider
     self._listeners = listeners
     self._buffer = buffer
+    self._directMode = False
 
-    self._directInPort = None
-    self._inPortListeners = None
     
-    self._directNewData = False
-    self._valueMutex = threading.RLock()
-    self._value = None
 
     if not self._buffer:
       self._buffer = self.createBuffer(info)
@@ -189,14 +185,7 @@
   #
   # virtual ReturnCode write(const cdrMemoryStream& data);
   def write(self, data):
-    if self._directInPort is not None:
-      
-      guard = OpenRTM_aist.ScopedLock(self._valueMutex)
-      self._value = data
-      self._directNewData = True
-      
-      del guard
-      
+    if self._directMode:
       return self.PORT_OK
     # data -> (conversion) -> CDR stream
     cdr_data = None
@@ -242,10 +231,8 @@
       OpenRTM_aist.CdrBufferFactory.instance().deleteObject(self._buffer)
     self._buffer = 0
 
-    if self._directInPort:
-      self._directInPort.removeOutPortConnector(self)
-      self._directInPort = None
 
+
     return self.PORT_OK
 
 
@@ -343,77 +330,15 @@
       self._listeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_DISCONNECT].notify(self._profile)
     return
 
-
   ##
   # @if jp
-  # @brief ¥Ç¡¼¥¿¤ò¥À¥¤¥ì¥¯¥È¤Ë½ñ¤­¹þ¤à¤¿¤á¤ÎInPort¤Î¥µ¡¼¥Ð¥ó¥È¤òÀßÄꤹ¤ë
-  #
-  # @param self
-  # @param directInPort InPort¤Î¥µ¡¼¥Ð¥ó¥È
-  # @return True: ÀßÄê¤ËÀ®¸ù False: ´û¤ËÀßÄêºÑ¤ß¤Î¤¿¤á¼ºÇÔ
+  # @brief ¥À¥¤¥ì¥¯¥ÈÀܳ¥â¡¼¥É¤ËÀßÄê
   # @else
   # @brief 
-  #
-  # @param self
-  # @param directInPort 
-  # @return 
   # @endif
-  #
-  # bool setPorts(InPortBase* directInPort, OutPortBase* outPort);
-  def setInPort(self, directInPort):
-    if self._directInPort is not None:
-      return False
-    self._directInPort = directInPort
-    self._inPortListeners = self._directInPort._listeners
-    
-    self._directInPort.addOutPortConnector(self)
-    return True
+  # void onDisconnect()
+  def setDirectMode(self):
+    self._directMode = True
+  
 
-  ##
-  # @if jp
-  #
-  # @brief ¥Ç¡¼¥¿¤ò¥À¥¤¥ì¥¯¥È¤ËÆɤ߹þ¤à
-  #
-  # @param self
-  # @return ȽÄê(¥Ç¡¼¥¿¤¬½ñ¤­¹þ¤Þ¤ì¤Æ¤¤¤Ê¤±¤ì¤ÐTrue)¡¢Æɤ߹þ¤à¥Ç¡¼¥¿
-  #
-  # @else
-  # @brief 
-  #
-  # @param self
-  # @param data 
-  # @endif
-  # DataType* read()
-  def read(self):
-    guard = OpenRTM_aist.ScopedLock(self._valueMutex)
-    if not self.isNew():
-        self._listeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_BUFFER_EMPTY].notify(self._profile)
-        self._inPortListeners.connector_[OpenRTM_aist.ConnectorListenerType.ON_SENDER_EMPTY].notify(self._profile)
-        self._rtcout.RTC_TRACE("ON_BUFFER_EMPTY(OutPort), ")
-        self._rtcout.RTC_TRACE("ON_SENDER_EMPTY(InPort) ")
-        self._rtcout.RTC_TRACE("callback called in direct mode.")
-        return False, ""
-    
-    data = self._value
-    ret = self._directNewData
-    self._directNewData = False
-    del guard
-    
-    
-    self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_READ].notify(self._profile, data)
-    self._rtcout.RTC_TRACE("ON_BUFFER_READ(OutPort), ")
-    self._rtcout.RTC_TRACE("callback called in direct mode.")
-    self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_SEND].notify(self._profile, data)
-    self._rtcout.RTC_TRACE("ON_SEND(OutPort), ")
-    self._rtcout.RTC_TRACE("callback called in direct mode.")
-    self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data)
-    self._rtcout.RTC_TRACE("ON_RECEIVED(InPort), ")
-    self._rtcout.RTC_TRACE("callback called in direct mode.")
-    self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_WRITE].notify(self._profile, data)
-    self._rtcout.RTC_TRACE("ON_BUFFER_WRITE(InPort), ")
-    self._rtcout.RTC_TRACE("callback called in direct mode.")
-    
-    return ret, data
 
-  def isNew(self):
-    return self._directNewData
\ No newline at end of file

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPushConnector.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPushConnector.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/OutPortPushConnector.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -239,20 +239,20 @@
 
     if self._directInPort is not None:
       if self._directInPort.isNew():
-        self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_OVERWRITE].notify(self._profile, data)
-        self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_OVERWRITE].notify(self._profile, data)
-        self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVER_FULL].notify(self._profile, data)
-        self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVER_FULL].notify(self._profile, data)
+        #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_OVERWRITE].notify(self._profile, data)
+        #self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_OVERWRITE].notify(self._profile, data)
+        #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVER_FULL].notify(self._profile, data)
+        #self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVER_FULL].notify(self._profile, data)
         self._rtcout.RTC_TRACE("ONBUFFER_OVERWRITE(InPort,OutPort), ")
         self._rtcout.RTC_TRACE("ON_RECEIVER_FULL(InPort,OutPort) ")
         self._rtcout.RTC_TRACE("callback called in direct mode.")
-      self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_WRITE].notify(self._profile, data)
-      self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_WRITE].notify(self._profile, data)
+      #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_WRITE].notify(self._profile, data)
+      #self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_BUFFER_WRITE].notify(self._profile, data)
       self._rtcout.RTC_TRACE("ON_BUFFER_WRITE(InPort,OutPort), ")
       self._rtcout.RTC_TRACE("callback called in direct mode.")
       self._directInPort.write(data)
-      self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data)
-      self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data)
+      #self._listeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data)
+      #self._inPortListeners.connectorData_[OpenRTM_aist.ConnectorDataListenerType.ON_RECEIVED].notify(self._profile, data)
       self._rtcout.RTC_TRACE("ON_RECEIVED(InPort,OutPort), ")
       self._rtcout.RTC_TRACE("callback called in direct mode.")
       return self.PORT_OK

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Properties.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Properties.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/Properties.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -780,11 +780,11 @@
       key = []
       value = []
       self.splitKeyValue(pline, key, value)
-      key[0] = OpenRTM_aist.unescape(key)
+      key[0] = OpenRTM_aist.unescape(key[0])
       OpenRTM_aist.eraseHeadBlank(key)
       OpenRTM_aist.eraseTailBlank(key)
 
-      value[0] = OpenRTM_aist.unescape(value)
+      value[0] = OpenRTM_aist.unescape(value[0])
       OpenRTM_aist.eraseHeadBlank(value)
       OpenRTM_aist.eraseTailBlank(value)
 

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/StringUtil.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/StringUtil.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/StringUtil.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -14,6 +14,7 @@
 #         Advanced Industrial Science and Technology (AIST), Japan
 #     All rights reserved.
 
+import os
 import sys
 if sys.version_info[0] == 3:
     long = int
@@ -171,7 +172,7 @@
 # 
 # @endif
 def escape(_str):
-  return for_each(_str[0], escape_functor())._str
+  return for_each(_str, escape_functor())._str
 
 
 ##
@@ -199,7 +200,7 @@
 # "\"" -> "  <br>
 # @endif
 def unescape(_str):
-  return for_each(_str[0], unescape_functor())._str
+  return for_each(_str, unescape_functor())._str
 
 
 ##
@@ -651,3 +652,92 @@
 # @endif
 def toArgv(args):
   return args
+
+
+
+
+##
+# @if jp
+# @brief URL¥Ñ¥é¥á¡¼¥¿¤òmapstring¤Ëʬ²ò¤·¤ÆÊÖ¤¹
+#
+# URL¥Ñ¥é¥á¡¼¥¿É½¸½ something?key0=value0&key1=value1.... ¤Î¤¦¤Á
+# '?' °Ê¹ß¤ÎÉôʬ¤òʬ²ò¤·¤Æ¡¢std::map<std::string, std::string> ·Á¼°
+# ¤ËÊÑ´¹¤¹¤ë¡£Í¿¤¨¤é¤ì¤¿Ê¸»úÎó¤òº¸¤«¤é¥µ¡¼¥Á¤·¡¢'?' ¤è¤ê±¦Â¦¤ÎÉôʬ¤Ë
+# ¤Ä¤¤¤Æ²òÀϤò¹Ô¤¦¡£'&'¤Çʬ³ä¤·¡¢º¸¤«¤é '=' ¤ò¸¡º÷¤·¡¢ºÇ½é¤Î '=' ¤Î
+# ±¦ÊդȺ¸ÊÕ¤ò¤½¤ì¤¾¤ì¡¢key ¤È value ¤È¤·¤Æ map ¤Ë³ÊǼ¤¹¤ë¡£
+#
+# @param str ʬ²òÂоÝʸ»úÎó
+# @return mapstring ·¿¤Î key/value¥Ç¡¼¥¿
+#
+#
+# @else
+# @brief Investigate whether the given string is URL or not
+#
+# URL parameter description such as
+# something?key0=value0&key1=value1.... is analyzed. Right hand
+# side string of '?' character is decomposed and it is converted
+# into std::map<std::string, std::string> type.The following string
+# are devided by '&' and then '=' character is
+# searched. Right-hand-side value and left-hand-side value of '='
+# are stored as key and value in the map.
+#
+# @param str The target string for decomposed
+#
+# @return decomposed key-values in map
+#
+# @endif
+def urlparam2map(_str):
+    qpos = _str.find("?")
+    if qpos == -1:
+        qpos = 0
+    else:
+        qpos+=1
+    tmp = _str[qpos:].split("&")
+    retmap = {}
+    for v in tmp:
+        pos = v.find("=")
+        if pos != -1:
+            retmap[v[0:pos]] = v[pos+1:]
+        else:
+            retmap[v] = ""
+    return retmap
+
+##
+# @if jp
+# @brief ʸ»úÎóÃæ¤Î´Ä¶­ÊÑ¿ô¤òÃÖ¤­´¹¤¨¤ë
+#
+# ʸ»úÎóÃæ¤Ë${}¤Ç°Ï¤Þ¤ì¤¿Ê¸»úÎ󤬤¢¤ë¾ì¹ç¤Ë¡¢´Ä¶­ÊÑ¿ô¤ÈÃÖ¤­´¹¤¨¤ë
+# Î㡧${RTM_ROOT}\bin -> C:\Program Files (x86)\OpenRTM-aist\1.1.2\
+#
+# @param _str ÃÖ¤­´¹¤¨Á°¤Îʸ»úÎó
+# @return ÃÖ¤­´¹¤¨¸å¤Îʸ»úÎó
+#
+#
+# @else
+# @brief 
+#
+# @param _str
+#
+# @return 
+#
+# @endif
+def replaceEnv(_str):
+    tmp = _str.split("${")
+    if len(tmp) < 2:
+        return _str
+    ret = []
+    for v in tmp:
+        tmp2 = v.split("}")
+        if len(tmp2) == 2:
+            if tmp2[0] in os.environ:
+                ret.append(os.environ[tmp2[0]])
+            ret.append(tmp2[1])
+            
+        else:
+            ret.append(v)
+    ret_str = ""
+    for s in ret:
+        ret_str = ret_str + s
+    return ret_str
+    
+        
\ No newline at end of file

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ext/sdo/observer/rtc.conf
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ext/sdo/observer/rtc.conf	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/ext/sdo/observer/rtc.conf	2018-02-08 01:13:55 UTC (rev 940)
@@ -5,4 +5,4 @@
 #logger.file_name: rtc%p.log,    STDOUT
 #manager.naming_formats: %n.mgr
 manager.modules.load_path:  .
-manager.modules.preload: ComponentObserverConsumer
+#manager.modules.preload: ComponentObserverConsumer

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/utils/rtcprof/rtcprof.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/utils/rtcprof/rtcprof.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/OpenRTM_aist/utils/rtcprof/rtcprof.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -61,6 +61,9 @@
   # for new
   comp_spec_name = classname+"_spec"
 
+  with open(str(fullname)) as f:
+    if f.read().find(comp_spec_name) == -1:
+      return
   try:
     imp_file = __import__(basename.split(".")[0])
   except:

Modified: branches/RELENG_1_2/OpenRTM-aist-Python/setup.py
===================================================================
--- branches/RELENG_1_2/OpenRTM-aist-Python/setup.py	2018-02-06 02:53:04 UTC (rev 939)
+++ branches/RELENG_1_2/OpenRTM-aist-Python/setup.py	2018-02-08 01:13:55 UTC (rev 940)
@@ -213,7 +213,8 @@
   "RTC.idl",
   "SDOPackage.idl",
   "SharedMemory.idl",
-  "IORProfile.idl"
+  "IORProfile.idl",
+  "../ext/sdo/observer/ComponentObserver.idl"
   ]
 baseidl_mods  = ["RTM", "RTC", "SDOPackage", "OpenRTM"]
 baseidl_path  = os.path.normpath(current_dir + "/" + baseidl_dir)



More information about the openrtm-commit mailing list