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