rtm.py
Go to the documentation of this file.
00001 from omniORB import CORBA, any, cdrUnmarshal, cdrMarshal
00002 import CosNaming
00003 
00004 import OpenRTM_aist
00005 import RTC, OpenRTM, SDOPackage, RTM
00006 from OpenRTM import CdrData, OutPortCdr, InPortCdr
00007 from RTC import *
00008 
00009 import sys
00010 import string, math, socket
00011 import os
00012 import time
00013 import re
00014 
00015 ##
00016 # \brief root naming context
00017 #
00018 rootnc = None
00019 nshost = None
00020 nsport = None
00021 mgrhost = None
00022 mgrport = None
00023 
00024 ##
00025 # \brief wrapper class of RT component
00026 #
00027 class RTcomponent:
00028     ##
00029     # \brief constructor
00030     # \param self this object
00031     # \param ref IOR of RT component
00032     def __init__(self, ref):
00033         self.ref = ref
00034         self.owned_ecs = ref.get_owned_contexts()
00035         self.ec = self.owned_ecs[0]
00036         self.ports = {}
00037         ports = self.ref.get_ports()
00038         for p in ports:
00039             prof = p.get_port_profile()
00040             name = prof.name.split('.')[1]
00041             self.ports[name] = p
00042 
00043     ##
00044     # \brief get IOR of port
00045     # \param self this object
00046     # \param name name of the port
00047     # \return IOR of the port
00048     def port(self, name):
00049         try:
00050             p = self.ports[unicode(name)]
00051         except KeyError:
00052             p = findPort(self.ref, name)
00053             self.ports[unicode(name)] = p
00054         return p
00055 
00056     ##
00057     # \brief get IOR of the service
00058     # \param self this object
00059     # \param instance_name instance name of the service
00060     # \param type_name type name of hte service
00061     # \param port_name port name which provides the service
00062     # \return IOR of the service
00063     def service(self, instance_name, type_name="", port_name=""):
00064         return findService(self, port_name, type_name, instance_name)
00065 
00066     ##
00067     # \brief update default configuration set
00068     # \param self this object
00069     # \param nvlist list of pairs of name and value
00070     # \return True if all values are set correctly, False otherwise
00071     def setConfiguration(self, nvlist):
00072         return setConfiguration(self.ref, nvlist)
00073 
00074     ##
00075     # \brief update value of the default configuration set
00076     # \param self this object
00077     # \param name name of the property
00078     # \param value new value of the property
00079     # \return True if all values are set correctly, False otherwise
00080     def setProperty(self, name, value):
00081         return self.setConfiguration([[name, value]])
00082 
00083     ##
00084     # \brief get name-value list of the default configuration set
00085     # \param self this object
00086     # \return name-value list of the default configuration set
00087     def getProperties(self):
00088         return getConfiguration(self.ref)
00089 
00090     ##
00091     # \brief get value of the property in the default configuration set
00092     # \param self this object
00093     # \param name name of the property
00094     # \return value of the property or None if the property is not found
00095     def getProperty(self, name):
00096         cfg = self.ref.get_configuration()
00097         cfgsets = cfg.get_configuration_sets()
00098         if len(cfgsets) == 0:
00099             print("configuration set is not found")
00100             return None
00101         cfgset = cfgsets[0]
00102         for d in cfgset.configuration_data:
00103             if d.name == name:
00104                 return any.from_any(d.value)
00105         return None
00106 
00107     ##
00108     # \brief activate this component
00109     # \param self this object
00110     # \param ec execution context used to activate this component
00111     # \param timeout maximum duration to wait for activation
00112     # \return True if activated successfully, False otherwise
00113     def start(self, ec=None, timeout=3.0):
00114         if ec == None:
00115             ec = self.ec
00116         if ec != None:
00117             if self.isActive(ec):
00118                 return True
00119             ret = ec.activate_component(self.ref)
00120             if  ret != RTC.RTC_OK:
00121                 print ('[rtm.py] \033[31m   Failed to start %s(%s)\033[0m' % \
00122                        (self.name(), ret))
00123                 return False
00124             tm = 0 
00125             while tm < timeout:
00126                 if self.isActive(ec):
00127                     return True
00128                 time.sleep(0.01)
00129                 tm += 0.01
00130         print ('[rtm.py] \033[31m   Failed to start %s(timeout)\033[0m' % \
00131                self.name())
00132         return False
00133 
00134     ##
00135     # \brief deactivate this component
00136     # \param self this object
00137     # \param ec execution context used to deactivate this component
00138     # \param timeout maximum duration to wait for deactivation
00139     # \return True if deactivated successfully, False otherwise
00140     def stop(self, ec=None, timeout=3.0):
00141         if ec == None:
00142             ec = self.ec
00143         if ec != None:
00144             if self.isInactive(ec):
00145                 return True
00146             ret = ec.deactivate_component(self.ref)
00147             if  ret != RTC.RTC_OK:
00148                 print ('[rtm.py] \033[31m   Failed to stop %s(%s)\033[0m' % \
00149                        (self.name(), ret))
00150                 return False
00151             tm = 0
00152             while tm < timeout:
00153                 if self.isInactive(ec):
00154                     return True
00155                 time.sleep(0.01)
00156                 tm += 0.01
00157         print ('[rtm.py] \033[31m   Failed to stop %s(timeout)\033[0m' % \
00158                self.name())
00159         return False
00160 
00161     ##
00162     # \brief reset this component
00163     # \param self this object
00164     # \param ec execution context used to reset this component
00165     # \return True if reseted successfully, False otherwise
00166     def reset(self, ec=None, timeout=3.0):
00167         if self.getLifeCycleState(ec) != RTC.ERROR_STATE:
00168             return True
00169         if ec == None:
00170             ec = self.ec
00171         return ec.reset_component(self.ref) == RTC.RTC_OK
00172     ##
00173     # \brief get life cycle state of the main execution context
00174     # \param self this object
00175     # \param ec execution context from which life cycle state is obtained
00176     # \return one of LifeCycleState value or None if the main execution context is not set
00177     def getLifeCycleState(self, ec=None):
00178         if ec == None:
00179             ec = self.ec
00180         if ec != None:
00181             return ec.get_component_state(self.ref)
00182         else:
00183             return None
00184 
00185     ##
00186     # \brief check the main execution context is active or not
00187     # \param ec execution context
00188     # \retval 1 this component is active
00189     # \retval 0 this component is not active
00190     def isActive(self, ec=None):
00191         return RTC.ACTIVE_STATE == self.getLifeCycleState(ec)
00192 
00193     ##
00194     # \brief check the main execution context is inactive or not
00195     # \param ec execution context
00196     # \retval 1 this component is inactive
00197     # \retval 0 this component is not inactive
00198     def isInactive(self, ec=None):
00199         return RTC.INACTIVE_STATE == self.getLifeCycleState(ec)
00200 
00201     ##
00202     # \brief get instance name
00203     # \return instance name
00204     def name(self):
00205         cprof = self.ref.get_component_profile()
00206         return cprof.instance_name
00207 
00208 ##
00209 # \brief wrapper class of RTCmanager
00210 #
00211 class RTCmanager:
00212     ##
00213     # \brief constructor
00214     # \param self this object
00215     # \param ref IOR of RTCmanager
00216     def __init__(self, ref):
00217         self.ref = ref
00218         uname = os.uname()[0]
00219         if uname == "Darwin":
00220             self.soext = ".dylib"
00221         else:
00222             self.soext = ".so"
00223 
00224     ##
00225     # \brief load RT component factory
00226     # \param self this object
00227     # \param basename basename of the shared library
00228     # \param initfunc a function called when the shared library is loaded. If
00229     #  not specified, basename+"Init" is called.
00230     def load(self, basename, initfunc=""):
00231         path = basename + self.soext
00232         if initfunc == "":
00233             basename + "Init"
00234         try:
00235             self.ref.load_module(path, initfunc)
00236         except:
00237             print("failed to load", path)
00238 
00239     ##
00240     # \brief create an instance of RT component
00241     # \param self this object
00242     # \param module name of RT component factory
00243     # \param name name of RT component instance
00244     # \return an object of RTcomponent
00245     def create(self, module, name=None):
00246         if name != None:
00247             rtc = findRTC(name)
00248             if rtc != None:
00249                 print('RTC named "' + name + '" already exists.')
00250                 return rtc
00251         args = module
00252         if name != None:
00253             args += '?instance_name=' + name
00254         ref = self.ref.create_component(args)
00255         if ref == None:
00256             return None
00257         else:
00258             return RTcomponent(ref)
00259 
00260     ##
00261     # \brief create an instance of RT component
00262     # \param self this object
00263     # \param name name of RT component instance
00264     def delete(self, name):
00265         # ref = self.ref.delete_component(name)
00266         ref = findRTC(name).ref.exit() # delte_component did not actually kill component, so use rtc.exit https://github.com/fkanehiro/hrpsys-base/pull/512#issuecomment-80430387
00267         if ref == RTC_OK:
00268             return True
00269         else:
00270             return False
00271 
00272     ##
00273     # \brief get list of factory names
00274     # \return list of factory names
00275     def get_factory_names(self):
00276         fs = []
00277         fps = self.ref.get_factory_profiles()
00278         for afp in fps:
00279             for p in afp.properties:
00280                 if p.name == "implementation_id":
00281                     fs.append(any.from_any(p.value))
00282         return fs
00283 
00284     ##
00285     # \brief get list of components
00286     # \return list of components
00287     def get_components(self):
00288         cs = []
00289         crefs = self.ref.get_components()
00290         for cref in crefs:
00291             c = RTcomponent(cref)
00292             cs.append(c)
00293         return cs
00294 
00295     ##
00296     # \brief restart Manager
00297     def restart(self):
00298         self.ref.shutdown()
00299         time.sleep(1)
00300 
00301 ##
00302 # \brief unbind an object reference 
00303 # \param name name of the object
00304 # \param kind kind of the object
00305 #
00306 def unbindObject(name, kind):
00307     nc = NameComponent(name, kind)
00308     path = [nc]
00309     rootnc.unbind(path)
00310     return None
00311 
00312 ##
00313 # \brief initialize ORB 
00314 #
00315 def initCORBA():
00316     global rootnc, orb, nshost, nsport, mgrhost, mgrport
00317 
00318     # from omniorb's document
00319     # When CORBA::ORB_init() is called, the value for each configuration
00320     # parameter is searched for in the following order:
00321     #  Command line arguments
00322     #  Environment variables
00323     # so init_CORBA will follow this order
00324     # first check command line argument
00325 
00326     rtm_argv = [sys.argv[0]]    # extract rtm related args only
00327     for i in range(len(sys.argv)):
00328         if sys.argv[i] == '-o':
00329             rtm_argv.extend(['-o', sys.argv[i+1]])
00330 
00331     mc = OpenRTM_aist.ManagerConfig();
00332     mc.parseArgs(rtm_argv)
00333 
00334     if nshost != None: # these values can be set via other script like "import rtm; rtm.nshost=XXX"
00335         print("\033[34m[rtm.py] nshost already set as " + str(nshost) + "\033[0m")
00336     else:
00337         try:
00338             nshost = mc._argprop.getProperty("corba.nameservers").split(":")[0]
00339             if not nshost:
00340                 raise
00341         except:
00342             nshost = socket.gethostname() # default
00343             print("\033[34m[rtm.py] Failed to parse corba.nameservers, use " + str(nshost) + " as nshost \033[0m")
00344 
00345     if nsport != None:
00346         print("\033[34m[rtm.py] nsport already set as " + str(nsport) + "\033[0m")
00347     else:
00348         try:
00349             nsport = int(mc._argprop.getProperty("corba.nameservers").split(":")[1])
00350             if not nsport:
00351                 raise
00352         except:
00353             nsport = 15005  # default
00354             print("\033[34m[rtm.py] Failed to parse corba.nameservers, use " + str(nsport) + " as nsport \033[0m")
00355 
00356     if mgrhost != None: 
00357         print("\033[34m[rtm.py] mgrhost already set as " + str(mgrhost) + "\033[0m")
00358     else:
00359         mgrhost = nshost
00360 
00361     if mgrport != None: 
00362         print("\033[34m[rtm.py] mgrport already set as " + str(mgrport) + "\033[0m")
00363     else:
00364         try:
00365             mgrport = int(mc._argprop.getProperty("corba.master_manager").split(":")[1])
00366             if not mgrport:
00367                 raise
00368         except:
00369             mgrport = 2810  # default
00370             print("\033[34m[rtm.py] Failed to parse corba.master_manager, use " + str(mgrport) + "\033[0m")
00371 
00372     print("\033[34m[rtm.py] configuration ORB with %s:%s\033[0m"%(nshost, nsport))
00373     print("\033[34m[rtm.py] configuration RTCManager with %s:%s\033[0m"%(mgrhost, mgrport))
00374     os.environ['ORBInitRef'] = 'NameService=corbaloc:iiop:%s:%s/NameService' % \
00375                                (nshost, nsport)
00376 
00377     try:
00378         orb = CORBA.ORB_init(sys.argv, CORBA.ORB_ID)
00379         nameserver = orb.resolve_initial_references("NameService")
00380         rootnc = nameserver._narrow(CosNaming.NamingContext)
00381     except omniORB.CORBA.ORB.InvalidName:
00382         _, e, _ = sys.exc_info()
00383         sys.exit('[ERROR] Invalide Name (hostname=%s).\n' % (nshost) +
00384                  'Make sure the hostname is correct.\n' + str(e))
00385     except omniORB.CORBA.TRANSIENT:
00386         try:
00387             nameserver = orb.string_to_object('corbaloc:iiop:%s:%s/NameService'%(nshost, nsport))
00388             rootnc = nameserver._narrow(CosNaming.NamingContext)
00389         except:
00390             _, e, _ = sys.exc_info()
00391             sys.exit('[ERROR] Connection Failed with the Nameserver (hostname=%s port=%s).\n' % (nshost, nsport) +
00392                      'Make sure the hostname is correct and the Nameserver is running.\n' + str(e))
00393     except Exception:
00394         _, e, _ = sys.exc_info()
00395         print(str(e))
00396 
00397     return None
00398 
00399 ##
00400 # \brief get root naming context 
00401 # \param corbaloc location of NamingService
00402 # \return root naming context
00403 #
00404 def getRootNamingContext(corbaloc):
00405     props = System.getProperties()
00406 
00407     args = ["-ORBInitRef", corbaloc]
00408     orb = ORB.init(args, props)
00409 
00410     nameserver = orb.resolve_initial_references("NameService")
00411     return NamingContextHelper.narrow(nameserver)
00412 
00413 ##
00414 # \brief get IOR of the object
00415 # \param name name of the object
00416 # \param kind kind of the object
00417 # \param rnc root naming context. If it is not specified, global variable
00418 # rootnc is used
00419 # \return IOR of the object
00420 # 
00421 def findObject(name, kind="", rnc=None):
00422     nc = CosNaming.NameComponent(name, kind)
00423     path = [nc]
00424     if not rnc:
00425         rnc = rootnc
00426         if not rnc:
00427             print("[ERROR] findObject(%r,kind=%r,rnc=%r) rootnc is not found" % (name, kind, rnc))
00428     return rnc.resolve(path)
00429 
00430 ##
00431 # \brief get RTCmanager
00432 # \param hostname hostname where rtcd is running
00433 # \param rnc root naming context. If it is not specified, global variable rootnc
00434 # is used
00435 # \return an object of RTCmanager
00436 #
00437 def findRTCmanager(hostname=None, rnc=None):
00438     if not rootnc:
00439         print("[ERROR] findRTCmanager(hostname=%r,rnc=%r) rootnc is not defined, need to call initCORBA()" % \
00440               (hostname, rnc))
00441     if not hostname:
00442         hostname = nshost
00443         cxt = None
00444     if not hostname:
00445         hostname = socket.gethostname()
00446     try:
00447         socket.gethostbyaddr(hostname)
00448     except Exception:
00449         _, e, _ = sys.exc_info()
00450         sys.exit('[ERROR] %s\n' % (str(e)) + '[ERROR] Could not get hostname for %s\n' % (hostname) +
00451                  '[ERROR] Make sure that you set the target hostname and address in DNS or /etc/hosts in linux/unix.')
00452 
00453 
00454     def getManagerFromNS(hostname, mgr=None):
00455         try:
00456             obj = findObject("manager", "mgr", findObject(hostname, "host_cxt", rnc))
00457             mgr = RTCmanager(obj._narrow(RTM.Manager))
00458         except:
00459             mgr = None
00460         return mgr
00461 
00462     def getManagerDirectly(hostname, mgr=None):
00463         global orb, mgrport
00464         corbaloc = "corbaloc:iiop:" + hostname + ":" + str(mgrport) + "/manager"
00465         print("\033[34m[rtm.py] trying to findRTCManager on port" + str(mgrport) + "\033[0m")
00466         try:
00467             obj = orb.string_to_object(corbaloc)
00468             mgr = RTCmanager(obj._narrow(RTM.Manager))
00469         except:
00470             mgr = None
00471         return mgr
00472 
00473     try:
00474         import CORBA
00475     except:
00476         print('import CORBA failed in findRTCmanager and neglect it for old python environment.')
00477     # fqdn
00478     mgr = None
00479     hostnames = [hostname, hostname.split(".")[0],
00480                  socket.gethostbyaddr(hostname)[0],
00481                  socket.gethostbyaddr(hostname)[0].split(".")[0]]
00482     for h in hostnames:
00483         mgr = getManagerDirectly(h) or getManagerFromNS(h)
00484         if mgr:
00485             return mgr
00486     print("Manager not found")
00487     return None
00488 
00489 
00490 ##
00491 # \brief get RT component
00492 # \param name name of the RT component
00493 # \param rnc root naming context. If it is not specified, global variable
00494 # rootnc is used
00495 # \return an object of RTcomponent
00496 #
00497 def findRTC(name, rnc=None):
00498     try:
00499         obj = findObject(name, "rtc", rnc)
00500         try:
00501             rtc = RTcomponent(obj._narrow(RTC.RTObject))
00502         except TypeError:
00503             rtc = RTcomponent(obj._narrow(RTC.DataFlowComponent))
00504         cxts = rtc.ref.get_participating_contexts()
00505         if len(cxts) > 0:
00506             rtc.ec = cxts[0]
00507         return rtc
00508     except:
00509         return None
00510 
00511 ##
00512 # \brief get a port of RT component
00513 # \param rtc an object of RTcomponent
00514 # \param name name of the port
00515 # \return IOR of the port if the port is found, None otherwise
00516 #
00517 def findPort(rtc, name):
00518     ports = rtc.get_ports()
00519     cprof = rtc.get_component_profile()
00520     portname = cprof.instance_name + "." + name
00521     for p in ports:
00522         prof = p.get_port_profile()
00523         if prof.name == portname:
00524             return p
00525     return None
00526 
00527 ##
00528 # \brief set up execution context of the first RTC so that RTCs are executed
00529 # sequentially
00530 # \param rtcs sequence of RTCs
00531 # \param stopEC whether stop owned ECs of slave components
00532 #
00533 def serializeComponents(rtcs, stopEC=True):
00534     if len(rtcs) < 2:
00535         return
00536     ec = rtcs[0].ec
00537     for rtc in rtcs[1:]:
00538         try:
00539             if not ec._is_equivalent(rtc.ec):
00540                 if stopEC:
00541                     rtc.ec.stop()
00542                 if ec.add_component(rtc.ref) == RTC.RTC_OK:
00543                     rtc.ec = ec
00544                 else:
00545                     print('error in add_component()')
00546             else:
00547                 print(rtc.name() + 'is already serialized')
00548         except Exception:
00549             _, e, _ = sys.exc_info()
00550             print("[rtm.py] \033[31m   error in serialize %s of %s %s\033[0m" % (rtc.name(),  [[r, r.name()] for r in rtcs], str(e)))
00551             raise e
00552 
00553 ##
00554 # \brief check two ports are connected or not
00555 # \retval True connected
00556 # \retval False not connected
00557 #
00558 def isConnected(outP, inP):
00559     op = outP.get_port_profile()
00560     for con_prof in op.connector_profiles:
00561         ports = con_prof.ports
00562         if len(ports) == 2 and outP._is_equivalent(ports[0]) and \
00563            inP._is_equivalent(ports[1]):
00564             return True
00565     return False
00566 
00567 ##
00568 # \brief disconnect ports
00569 # \param outP IOR of outPort
00570 # \param inP IOR of inPort
00571 # \return True disconnected successfully, False otherwise
00572 #
00573 def disconnectPorts(outP, inP):
00574     op = outP.get_port_profile()
00575     iname = inP.get_port_profile().name
00576     for con_prof in op.connector_profiles:
00577         ports = con_prof.ports
00578         if len(ports) == 2:
00579             pname = ports[1].get_port_profile().name
00580             if pname == iname:
00581                 print('[rtm.py]    Disconnect %s - %s' %(op.name, iname))
00582                 outP.disconnect(con_prof.connector_id)
00583                 return True
00584     return False
00585 
00586 ##
00587 # \brief get data type of a port
00588 # \param port IOR of port
00589 # \return data type
00590 #
00591 def dataTypeOfPort(port):
00592     prof = port.get_port_profile()
00593     prop = prof.properties
00594     for p in prop:
00595         if p.name == "dataport.data_type":
00596             return any.from_any(p.value)
00597     return None
00598 
00599 ##
00600 # \brief connect ports
00601 # \param outP IOR of outPort 
00602 # \param inPs an IOR or a list of IORs of inPort
00603 # \param subscription subscription type. "flush", "new" or "periodic"
00604 # \param dataflow dataflow type. "Push" or "Pull"
00605 # \param bufferlength length of data buffer
00606 # \param rate communication rate for periodic mode[Hz]
00607 #
00608 def connectPorts(outP, inPs, subscription="flush", dataflow="Push", bufferlength=1, rate=1000, pushpolicy="new", interfaceType="corba_cdr"):
00609     if not isinstance(inPs, list):
00610         inPs = [inPs]
00611     if not outP:
00612         print('[rtm.py] \033[31m   Failed to connect %s to %s(%s)\033[0m' % \
00613               (outP, [inP.get_port_profile().name if inP else inP for inP in inPs], inPs))
00614         return
00615     for inP in inPs:
00616         if not inP:
00617             print('[rtm.py] \033[31m   Failed to connect %s to %s(%s)\033[0m' % \
00618                   (outP.get_port_profile().name, inP, inPs))
00619             continue
00620         if isConnected(outP, inP) == True:
00621             print('[rtm.py]      %s and %s are already connected' % \
00622                   (outP.get_port_profile().name, inP.get_port_profile().name))
00623             continue
00624         if dataTypeOfPort(outP) != dataTypeOfPort(inP):
00625             print('[rtm.py] \033[31m     %s and %s have different data types\033[0m' % \
00626                   (outP.get_port_profile().name, inP.get_port_profile().name))
00627             continue
00628         nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any(interfaceType))
00629         nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any(dataflow))
00630         nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any(subscription))
00631         nv4 = SDOPackage.NameValue("dataport.buffer.length", any.to_any(str(bufferlength)))
00632         nv5 = SDOPackage.NameValue("dataport.publisher.push_rate", any.to_any(str(rate)))
00633         nv6 = SDOPackage.NameValue("dataport.publisher.push_policy", any.to_any(pushpolicy))
00634         nv7 = SDOPackage.NameValue("dataport.data_type", any.to_any(dataTypeOfPort(outP)))
00635         con_prof = RTC.ConnectorProfile("connector0", "", [outP, inP],
00636                                         [nv1, nv2, nv3, nv4, nv5, nv6, nv7])
00637         print('[rtm.py]    Connect ' + outP.get_port_profile().name + ' - ' + \
00638               inP.get_port_profile().name+' (dataflow_type='+dataflow+', subscription_type='+ subscription+', bufferlength='+str(bufferlength)+', push_rate='+str(rate)+', push_policy='+pushpolicy+')')
00639         ret, prof = inP.connect(con_prof)
00640         if ret != RTC.RTC_OK:
00641             print("failed to connect")
00642             continue
00643         # confirm connection
00644         if isConnected(outP, inP) == False:
00645             print("connet() returned RTC_OK, but not connected")
00646 
00647 ##
00648 # \brief convert data into CDR format
00649 # \param data data to be converted
00650 # \return converted data in CDR format
00651 #
00652 def data2cdr(data):
00653     return cdrMarshal(any.to_any(data).typecode(), data, True)
00654 
00655 ##
00656 # \brief get class object from class name
00657 # \param fullname class name
00658 # \return class object
00659 #
00660 def classFromString(fullname):
00661     component_path = fullname.split('.')
00662     package_name = component_path[0]
00663     component_path = component_path[1:]
00664     attr = None
00665     while component_path:
00666         class_name = component_path[0]
00667         component_path = component_path[1:]
00668         if attr:
00669             attr = getattr(attr, class_name)
00670         else:
00671             __import__(str(package_name))
00672             attr = getattr(sys.modules[package_name], class_name)
00673     return attr
00674 
00675 ##
00676 # \brief convert data from CDR format
00677 # \param cdr in CDR format 
00678 # \param classname class name of the data
00679 # \return converted data
00680 #
00681 def cdr2data(cdr, classname):
00682     return cdrUnmarshal(any.to_any(classFromString(classname)).typecode(), cdr, True)
00683 
00684 
00685 
00686 connector_list = []
00687 
00688 ##
00689 # \brief write data to a data port      
00690 # \param port reference of data port
00691 # \param data data to be written
00692 # \param tm If disconnect==True, a connection to write data is disconnected
00693 # after this time
00694 # \param disconnect If True, a connection is disconnected after tm and if not,
00695 # the connection must be disconnected by a user
00696 #
00697 def writeDataPort(port, data, tm=1.0, disconnect=True):
00698     global connector_list, orb
00699     
00700     connector_name = "writeDataPort"
00701     
00702     
00703     
00704     prof = None
00705     
00706     for p in connector_list:
00707         if p["port"]._is_equivalent(port):
00708             if port.get_connector_profile(p["prof"].connector_id).name == connector_name:
00709                 prof = p["prof"]
00710             else:
00711                 connector_list.remove(p)
00712                 
00713             
00714 
00715 
00716     if prof is None:      
00717         nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any("corba_cdr"))
00718         nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any("Push"))
00719         nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any("flush"))
00720         con_prof = RTC.ConnectorProfile(connector_name, "", [port], [nv1, nv2, nv3])
00721         
00722         ret, prof = port.connect(con_prof)
00723         
00724         if ret != RTC.RTC_OK:
00725             print("failed to connect")
00726             return None
00727         connector_list.append({"port":port,"prof":prof})
00728         
00729         
00730     for p in prof.properties:
00731         if p.name == 'dataport.corba_cdr.inport_ior':
00732             ior = any.from_any(p.value)
00733             obj = orb.string_to_object(ior)
00734             inport = obj._narrow(InPortCdr)
00735             cdr = data2cdr(data)
00736             if inport.put(cdr) != OpenRTM.PORT_OK:
00737                 print("failed to put")
00738             if disconnect:
00739                 time.sleep(tm)
00740                 port.disconnect(prof.connector_id)
00741                 for p in connector_list:
00742                     if prof.connector_id == p["prof"].connector_id:
00743                         connector_list.remove(p)
00744             else:
00745                 return prof.connector_id
00746     return None
00747 
00748 
00749 
00750 ##
00751 # \brief read data from a data port     
00752 # \param port reference of data port
00753 # \param timeout timeout[s] 
00754 # \return data
00755 #
00756 def readDataPort(port, timeout=1.0, disconnect=True):
00757     global connector_list, orb
00758 
00759     
00760     connector_name = "readDataPort"
00761     prof = None
00762     for p in connector_list:
00763         if p["port"]._is_equivalent(port):
00764             if port.get_connector_profile(p["prof"].connector_id).name == connector_name:
00765                 prof = p["prof"]
00766             else:
00767                 connector_list.remove(p)
00768                 
00769             
00770 
00771     
00772     
00773 
00774     pprof = port.get_port_profile()
00775     for prop in pprof.properties:
00776         if prop.name == "dataport.data_type":
00777             classname = any.from_any(prop.value)
00778     
00779     if prof is None:     
00780         
00781         nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any("corba_cdr"))
00782         nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any("Pull"))
00783         nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any("flush"))
00784         con_prof = RTC.ConnectorProfile(connector_name, "", [port], [nv1, nv2, nv3])
00785         
00786         ret, prof = port.connect(con_prof)
00787         
00788         if ret != RTC.RTC_OK:
00789             print("failed to connect")
00790             return None
00791         
00792         connector_list.append({"port":port,"prof":prof})
00793     
00794     for p in prof.properties:
00795         if p.name == 'dataport.corba_cdr.outport_ior':
00796             ior = any.from_any(p.value)
00797             obj = orb.string_to_object(ior)
00798             outport = obj._narrow(OutPortCdr)
00799             tm = 0
00800             while tm < timeout:
00801                 try:
00802                     ret, data = outport.get()
00803                     if ret == OpenRTM.PORT_OK:
00804                         if disconnect:
00805                             port.disconnect(prof.connector_id)
00806                             for p in connector_list:
00807                                 if prof.connector_id == p["prof"].connector_id:
00808                                     connector_list.remove(p)
00809                         
00810                         tokens = classname.split(':')
00811                         if len(tokens) == 3:  # for 1.1?
00812                             classname = tokens[1].replace('/', '.')
00813                         return cdr2data(data, classname)
00814                 except:
00815                     pass
00816                 time.sleep(0.1)
00817                 tm = tm + 0.1
00818                 
00819 
00820         
00821     return None
00822 
00823 ##
00824 # \brief 
00825 #
00826 def deleteAllConnector():
00827     global connector_list
00828     for port in connector_list:
00829         port["port"].disconnect(port["prof"].connector_id)
00830     del connector_list[:]
00831 
00832 ##
00833 # \brief get a service of RT component
00834 # \param rtc IOR of RT component
00835 # \param port_name port name of the port which provides the service
00836 # \param type_name type name of the service
00837 # \param instance_name name of the service
00838 # \return IOR of the service
00839 #
00840 def findService(rtc, port_name, type_name, instance_name):
00841     if port_name == "":
00842         prof = rtc.ref.get_component_profile()
00843         # print("RTC name:",prof.instance_name)
00844         port_prof = prof.port_profiles
00845     else:
00846         p = rtc.port(port_name)
00847         if p == None:
00848             print("can't find a port named" + port_name)
00849             return None
00850         else:
00851             port_prof = [p.get_port_profile()]
00852     port = None
00853     for pp in port_prof:
00854         # print("name:", pp.name)
00855         ifs = pp.interfaces
00856         for aif in ifs:
00857             #print("IF name:", aif.instance_name)
00858             #print("IF type:", aif.type_name)
00859             if aif.instance_name == instance_name and \
00860                (type_name == "" or aif.type_name == type_name) and \
00861                aif.polarity == PROVIDED:
00862                 port = pp.port_ref
00863     if port == None:
00864         print("can't find a service named", instance_name)
00865         return None
00866     con_prof = RTC.ConnectorProfile("noname", "", [port], [])
00867     ret, con_prof = port.connect(con_prof)
00868     ior = any.from_any(con_prof.properties[0].value)
00869     return orb.string_to_object(ior)
00870 
00871 ##
00872 # \brief update default configuration set
00873 # \param rtc IOR of RT component
00874 # \param nvlist list of pairs of name and value
00875 # \return True if all values are set correctly, False otherwise
00876 #
00877 def setConfiguration(rtc, nvlist):
00878     ret = True
00879     cfg = rtc.get_configuration()
00880     cfgsets = cfg.get_configuration_sets()
00881     if len(cfgsets) == 0:
00882         print("configuration set is not found")
00883         return
00884     cfgset = cfgsets[0]
00885     for nv in nvlist:
00886         name = nv[0]
00887         value = nv[1]
00888         found = False
00889         for d in cfgset.configuration_data:
00890             if d.name == name:
00891                 d.value = any.to_any(value)
00892                 cfg.set_configuration_set_values(cfgset)
00893                 found = True
00894                 break
00895         if not found:
00896             ret = False
00897     cfg.activate_configuration_set('default')
00898     return ret
00899 
00900 ##
00901 # \brief get default configuration set
00902 # \param rtc IOR of RT component
00903 # \return default configuration set
00904 #
00905 def getConfiguration(rtc):
00906     cfg = rtc.get_configuration()
00907     cfgsets = cfg.get_configuration_sets()
00908     if len(cfgsets) == 0:
00909         print("configuration set is not found")
00910         return None
00911     ret = {}
00912     for nv in cfgsets[0].configuration_data:
00913         ret[nv.name] = any.from_any(nv.value)
00914     return ret
00915     
00916 
00917 ##
00918 # \brief narrow ior
00919 # \param ior ior
00920 # \param klass class name 
00921 # \param package package where the class is defined
00922 #
00923 def narrow(ior, klass, package="OpenHRP"):
00924     return ior._narrow(getattr(sys.modules[package], klass))
00925 
00926 ##
00927 # \brief check if jython or python
00928 # \return True if jython
00929 #
00930 def isJython():
00931     return sys.version.count("GCC") == 0
00932 
00933 
00934 if __name__ == '__main__':
00935     initCORBA()


hrpsys
Author(s): AIST, Fumio Kanehiro
autogenerated on Wed May 15 2019 05:02:18