-
Notifications
You must be signed in to change notification settings - Fork 86
/
rtm.py
935 lines (833 loc) · 30.2 KB
/
rtm.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
from omniORB import CORBA, any, cdrUnmarshal, cdrMarshal
import CosNaming
import OpenRTM_aist
import RTC, OpenRTM, SDOPackage, RTM
from OpenRTM import CdrData, OutPortCdr, InPortCdr
from RTC import *
import sys
import string, math, socket
import os
import time
import re
##
# \brief root naming context
#
rootnc = None
nshost = None
nsport = None
mgrhost = None
mgrport = None
##
# \brief wrapper class of RT component
#
class RTcomponent:
##
# \brief constructor
# \param self this object
# \param ref IOR of RT component
def __init__(self, ref):
self.ref = ref
self.owned_ecs = ref.get_owned_contexts()
self.ec = self.owned_ecs[0]
self.ports = {}
ports = self.ref.get_ports()
for p in ports:
prof = p.get_port_profile()
name = prof.name.split('.')[1]
self.ports[name] = p
##
# \brief get IOR of port
# \param self this object
# \param name name of the port
# \return IOR of the port
def port(self, name):
try:
p = self.ports[unicode(name)]
except KeyError:
p = findPort(self.ref, name)
self.ports[unicode(name)] = p
return p
##
# \brief get IOR of the service
# \param self this object
# \param instance_name instance name of the service
# \param type_name type name of hte service
# \param port_name port name which provides the service
# \return IOR of the service
def service(self, instance_name, type_name="", port_name=""):
return findService(self, port_name, type_name, instance_name)
##
# \brief update default configuration set
# \param self this object
# \param nvlist list of pairs of name and value
# \return True if all values are set correctly, False otherwise
def setConfiguration(self, nvlist):
return setConfiguration(self.ref, nvlist)
##
# \brief update value of the default configuration set
# \param self this object
# \param name name of the property
# \param value new value of the property
# \return True if all values are set correctly, False otherwise
def setProperty(self, name, value):
return self.setConfiguration([[name, value]])
##
# \brief get name-value list of the default configuration set
# \param self this object
# \return name-value list of the default configuration set
def getProperties(self):
return getConfiguration(self.ref)
##
# \brief get value of the property in the default configuration set
# \param self this object
# \param name name of the property
# \return value of the property or None if the property is not found
def getProperty(self, name):
cfg = self.ref.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print("configuration set is not found")
return None
cfgset = cfgsets[0]
for d in cfgset.configuration_data:
if d.name == name:
return any.from_any(d.value)
return None
##
# \brief activate this component
# \param self this object
# \param ec execution context used to activate this component
# \param timeout maximum duration to wait for activation
# \return True if activated successfully, False otherwise
def start(self, ec=None, timeout=3.0):
if ec == None:
ec = self.ec
if ec != None:
if self.isActive(ec):
return True
ret = ec.activate_component(self.ref)
if ret != RTC.RTC_OK:
print ('[rtm.py] \033[31m Failed to start %s(%s)\033[0m' % \
(self.name(), ret))
return False
tm = 0
while tm < timeout:
if self.isActive(ec):
return True
time.sleep(0.01)
tm += 0.01
print ('[rtm.py] \033[31m Failed to start %s(timeout)\033[0m' % \
self.name())
return False
##
# \brief deactivate this component
# \param self this object
# \param ec execution context used to deactivate this component
# \param timeout maximum duration to wait for deactivation
# \return True if deactivated successfully, False otherwise
def stop(self, ec=None, timeout=3.0):
if ec == None:
ec = self.ec
if ec != None:
if self.isInactive(ec):
return True
ret = ec.deactivate_component(self.ref)
if ret != RTC.RTC_OK:
print ('[rtm.py] \033[31m Failed to stop %s(%s)\033[0m' % \
(self.name(), ret))
return False
tm = 0
while tm < timeout:
if self.isInactive(ec):
return True
time.sleep(0.01)
tm += 0.01
print ('[rtm.py] \033[31m Failed to stop %s(timeout)\033[0m' % \
self.name())
return False
##
# \brief reset this component
# \param self this object
# \param ec execution context used to reset this component
# \return True if reseted successfully, False otherwise
def reset(self, ec=None, timeout=3.0):
if self.getLifeCycleState(ec) != RTC.ERROR_STATE:
return True
if ec == None:
ec = self.ec
return ec.reset_component(self.ref) == RTC.RTC_OK
##
# \brief get life cycle state of the main execution context
# \param self this object
# \param ec execution context from which life cycle state is obtained
# \return one of LifeCycleState value or None if the main execution context is not set
def getLifeCycleState(self, ec=None):
if ec == None:
ec = self.ec
if ec != None:
return ec.get_component_state(self.ref)
else:
return None
##
# \brief check the main execution context is active or not
# \param ec execution context
# \retval 1 this component is active
# \retval 0 this component is not active
def isActive(self, ec=None):
return RTC.ACTIVE_STATE == self.getLifeCycleState(ec)
##
# \brief check the main execution context is inactive or not
# \param ec execution context
# \retval 1 this component is inactive
# \retval 0 this component is not inactive
def isInactive(self, ec=None):
return RTC.INACTIVE_STATE == self.getLifeCycleState(ec)
##
# \brief get instance name
# \return instance name
def name(self):
cprof = self.ref.get_component_profile()
return cprof.instance_name
##
# \brief wrapper class of RTCmanager
#
class RTCmanager:
##
# \brief constructor
# \param self this object
# \param ref IOR of RTCmanager
def __init__(self, ref):
self.ref = ref
uname = os.uname()[0]
if uname == "Darwin":
self.soext = ".dylib"
else:
self.soext = ".so"
##
# \brief load RT component factory
# \param self this object
# \param basename basename of the shared library
# \param initfunc a function called when the shared library is loaded. If
# not specified, basename+"Init" is called.
def load(self, basename, initfunc=""):
path = basename + self.soext
if initfunc == "":
basename + "Init"
try:
self.ref.load_module(path, initfunc)
except:
print("failed to load", path)
##
# \brief create an instance of RT component
# \param self this object
# \param module name of RT component factory
# \param name name of RT component instance
# \return an object of RTcomponent
def create(self, module, name=None):
if name != None:
rtc = findRTC(name)
if rtc != None:
print('RTC named "' + name + '" already exists.')
return rtc
args = module
if name != None:
args += '?instance_name=' + name
ref = self.ref.create_component(args)
if ref == None:
return None
else:
return RTcomponent(ref)
##
# \brief create an instance of RT component
# \param self this object
# \param name name of RT component instance
def delete(self, name):
# ref = self.ref.delete_component(name)
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
if ref == RTC_OK:
return True
else:
return False
##
# \brief get list of factory names
# \return list of factory names
def get_factory_names(self):
fs = []
fps = self.ref.get_factory_profiles()
for afp in fps:
for p in afp.properties:
if p.name == "implementation_id":
fs.append(any.from_any(p.value))
return fs
##
# \brief get list of components
# \return list of components
def get_components(self):
cs = []
crefs = self.ref.get_components()
for cref in crefs:
c = RTcomponent(cref)
cs.append(c)
return cs
##
# \brief restart Manager
def restart(self):
self.ref.shutdown()
time.sleep(1)
##
# \brief unbind an object reference
# \param name name of the object
# \param kind kind of the object
#
def unbindObject(name, kind):
nc = NameComponent(name, kind)
path = [nc]
rootnc.unbind(path)
return None
##
# \brief initialize ORB
#
def initCORBA():
global rootnc, orb, nshost, nsport, mgrhost, mgrport
# from omniorb's document
# When CORBA::ORB_init() is called, the value for each configuration
# parameter is searched for in the following order:
# Command line arguments
# Environment variables
# so init_CORBA will follow this order
# first check command line argument
rtm_argv = [sys.argv[0]] # extract rtm related args only
for i in range(len(sys.argv)):
if sys.argv[i] == '-o':
rtm_argv.extend(['-o', sys.argv[i+1]])
mc = OpenRTM_aist.ManagerConfig();
mc.parseArgs(rtm_argv)
if nshost != None: # these values can be set via other script like "import rtm; rtm.nshost=XXX"
print("\033[34m[rtm.py] nshost already set as " + str(nshost) + "\033[0m")
else:
try:
nshost = mc._argprop.getProperty("corba.nameservers").split(":")[0]
if not nshost:
raise
except:
nshost = socket.gethostname() # default
print("\033[34m[rtm.py] Failed to parse corba.nameservers, use " + str(nshost) + " as nshost \033[0m")
if nsport != None:
print("\033[34m[rtm.py] nsport already set as " + str(nsport) + "\033[0m")
else:
try:
nsport = int(mc._argprop.getProperty("corba.nameservers").split(":")[1])
if not nsport:
raise
except:
nsport = 15005 # default
print("\033[34m[rtm.py] Failed to parse corba.nameservers, use " + str(nsport) + " as nsport \033[0m")
if mgrhost != None:
print("\033[34m[rtm.py] mgrhost already set as " + str(mgrhost) + "\033[0m")
else:
mgrhost = nshost
if mgrport != None:
print("\033[34m[rtm.py] mgrport already set as " + str(mgrport) + "\033[0m")
else:
try:
mgrport = int(mc._argprop.getProperty("corba.master_manager").split(":")[1])
if not mgrport:
raise
except:
mgrport = 2810 # default
print("\033[34m[rtm.py] Failed to parse corba.master_manager, use " + str(mgrport) + "\033[0m")
print("\033[34m[rtm.py] configuration ORB with %s:%s\033[0m"%(nshost, nsport))
print("\033[34m[rtm.py] configuration RTCManager with %s:%s\033[0m"%(mgrhost, mgrport))
os.environ['ORBInitRef'] = 'NameService=corbaloc:iiop:%s:%s/NameService' % \
(nshost, nsport)
try:
orb = CORBA.ORB_init(sys.argv, CORBA.ORB_ID)
nameserver = orb.resolve_initial_references("NameService")
rootnc = nameserver._narrow(CosNaming.NamingContext)
except omniORB.CORBA.ORB.InvalidName:
_, e, _ = sys.exc_info()
sys.exit('[ERROR] Invalide Name (hostname=%s).\n' % (nshost) +
'Make sure the hostname is correct.\n' + str(e))
except omniORB.CORBA.TRANSIENT:
try:
nameserver = orb.string_to_object('corbaloc:iiop:%s:%s/NameService'%(nshost, nsport))
rootnc = nameserver._narrow(CosNaming.NamingContext)
except:
_, e, _ = sys.exc_info()
sys.exit('[ERROR] Connection Failed with the Nameserver (hostname=%s port=%s).\n' % (nshost, nsport) +
'Make sure the hostname is correct and the Nameserver is running.\n' + str(e))
except Exception:
_, e, _ = sys.exc_info()
print(str(e))
return None
##
# \brief get root naming context
# \param corbaloc location of NamingService
# \return root naming context
#
def getRootNamingContext(corbaloc):
props = System.getProperties()
args = ["-ORBInitRef", corbaloc]
orb = ORB.init(args, props)
nameserver = orb.resolve_initial_references("NameService")
return NamingContextHelper.narrow(nameserver)
##
# \brief get IOR of the object
# \param name name of the object
# \param kind kind of the object
# \param rnc root naming context. If it is not specified, global variable
# rootnc is used
# \return IOR of the object
#
def findObject(name, kind="", rnc=None):
nc = CosNaming.NameComponent(name, kind)
path = [nc]
if not rnc:
rnc = rootnc
if not rnc:
print("[ERROR] findObject(%r,kind=%r,rnc=%r) rootnc is not found" % (name, kind, rnc))
return rnc.resolve(path)
##
# \brief get RTCmanager
# \param hostname hostname where rtcd is running
# \param rnc root naming context. If it is not specified, global variable rootnc
# is used
# \return an object of RTCmanager
#
def findRTCmanager(hostname=None, rnc=None):
if not rootnc:
print("[ERROR] findRTCmanager(hostname=%r,rnc=%r) rootnc is not defined, need to call initCORBA()" % \
(hostname, rnc))
if not hostname:
hostname = nshost
cxt = None
if not hostname:
hostname = socket.gethostname()
try:
socket.gethostbyaddr(hostname)
except Exception:
_, e, _ = sys.exc_info()
sys.exit('[ERROR] %s\n' % (str(e)) + '[ERROR] Could not get hostname for %s\n' % (hostname) +
'[ERROR] Make sure that you set the target hostname and address in DNS or /etc/hosts in linux/unix.')
def getManagerFromNS(hostname, mgr=None):
try:
obj = findObject("manager", "mgr", findObject(hostname, "host_cxt", rnc))
mgr = RTCmanager(obj._narrow(RTM.Manager))
except:
mgr = None
return mgr
def getManagerDirectly(hostname, mgr=None):
global orb, mgrport
corbaloc = "corbaloc:iiop:" + hostname + ":" + str(mgrport) + "/manager"
print("\033[34m[rtm.py] trying to findRTCManager on port" + str(mgrport) + "\033[0m")
try:
obj = orb.string_to_object(corbaloc)
mgr = RTCmanager(obj._narrow(RTM.Manager))
except:
mgr = None
return mgr
try:
import CORBA
except:
print('import CORBA failed in findRTCmanager and neglect it for old python environment.')
# fqdn
mgr = None
hostnames = [hostname, hostname.split(".")[0],
socket.gethostbyaddr(hostname)[0],
socket.gethostbyaddr(hostname)[0].split(".")[0]]
for h in hostnames:
mgr = getManagerDirectly(h) or getManagerFromNS(h)
if mgr:
return mgr
print("Manager not found")
return None
##
# \brief get RT component
# \param name name of the RT component
# \param rnc root naming context. If it is not specified, global variable
# rootnc is used
# \return an object of RTcomponent
#
def findRTC(name, rnc=None):
try:
obj = findObject(name, "rtc", rnc)
try:
rtc = RTcomponent(obj._narrow(RTC.RTObject))
except TypeError:
rtc = RTcomponent(obj._narrow(RTC.DataFlowComponent))
cxts = rtc.ref.get_participating_contexts()
if len(cxts) > 0:
rtc.ec = cxts[0]
return rtc
except:
return None
##
# \brief get a port of RT component
# \param rtc an object of RTcomponent
# \param name name of the port
# \return IOR of the port if the port is found, None otherwise
#
def findPort(rtc, name):
ports = rtc.get_ports()
cprof = rtc.get_component_profile()
portname = cprof.instance_name + "." + name
for p in ports:
prof = p.get_port_profile()
if prof.name == portname:
return p
return None
##
# \brief set up execution context of the first RTC so that RTCs are executed
# sequentially
# \param rtcs sequence of RTCs
# \param stopEC whether stop owned ECs of slave components
#
def serializeComponents(rtcs, stopEC=True):
if len(rtcs) < 2:
return
ec = rtcs[0].ec
for rtc in rtcs[1:]:
try:
if not ec._is_equivalent(rtc.ec):
if stopEC:
rtc.ec.stop()
if ec.add_component(rtc.ref) == RTC.RTC_OK:
rtc.ec = ec
else:
print('error in add_component()')
else:
print(rtc.name() + 'is already serialized')
except Exception:
_, e, _ = sys.exc_info()
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)))
raise e
##
# \brief check two ports are connected or not
# \retval True connected
# \retval False not connected
#
def isConnected(outP, inP):
op = outP.get_port_profile()
for con_prof in op.connector_profiles:
ports = con_prof.ports
if len(ports) == 2 and outP._is_equivalent(ports[0]) and \
inP._is_equivalent(ports[1]):
return True
return False
##
# \brief disconnect ports
# \param outP IOR of outPort
# \param inP IOR of inPort
# \return True disconnected successfully, False otherwise
#
def disconnectPorts(outP, inP):
op = outP.get_port_profile()
iname = inP.get_port_profile().name
for con_prof in op.connector_profiles:
ports = con_prof.ports
if len(ports) == 2:
pname = ports[1].get_port_profile().name
if pname == iname:
print('[rtm.py] Disconnect %s - %s' %(op.name, iname))
outP.disconnect(con_prof.connector_id)
return True
return False
##
# \brief get data type of a port
# \param port IOR of port
# \return data type
#
def dataTypeOfPort(port):
prof = port.get_port_profile()
prop = prof.properties
for p in prop:
if p.name == "dataport.data_type":
return any.from_any(p.value)
return None
##
# \brief connect ports
# \param outP IOR of outPort
# \param inPs an IOR or a list of IORs of inPort
# \param subscription subscription type. "flush", "new" or "periodic"
# \param dataflow dataflow type. "Push" or "Pull"
# \param bufferlength length of data buffer
# \param rate communication rate for periodic mode[Hz]
#
def connectPorts(outP, inPs, subscription="flush", dataflow="Push", bufferlength=1, rate=1000, pushpolicy="new", interfaceType="corba_cdr"):
if not isinstance(inPs, list):
inPs = [inPs]
if not outP:
print('[rtm.py] \033[31m Failed to connect %s to %s(%s)\033[0m' % \
(outP, [inP.get_port_profile().name if inP else inP for inP in inPs], inPs))
return
for inP in inPs:
if not inP:
print('[rtm.py] \033[31m Failed to connect %s to %s(%s)\033[0m' % \
(outP.get_port_profile().name, inP, inPs))
continue
if isConnected(outP, inP) == True:
print('[rtm.py] %s and %s are already connected' % \
(outP.get_port_profile().name, inP.get_port_profile().name))
continue
if dataTypeOfPort(outP) != dataTypeOfPort(inP):
print('[rtm.py] \033[31m %s and %s have different data types\033[0m' % \
(outP.get_port_profile().name, inP.get_port_profile().name))
continue
nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any(interfaceType))
nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any(dataflow))
nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any(subscription))
nv4 = SDOPackage.NameValue("dataport.buffer.length", any.to_any(str(bufferlength)))
nv5 = SDOPackage.NameValue("dataport.publisher.push_rate", any.to_any(str(rate)))
nv6 = SDOPackage.NameValue("dataport.publisher.push_policy", any.to_any(pushpolicy))
nv7 = SDOPackage.NameValue("dataport.data_type", any.to_any(dataTypeOfPort(outP)))
con_prof = RTC.ConnectorProfile("connector0", "", [outP, inP],
[nv1, nv2, nv3, nv4, nv5, nv6, nv7])
print('[rtm.py] Connect ' + outP.get_port_profile().name + ' - ' + \
inP.get_port_profile().name+' (dataflow_type='+dataflow+', subscription_type='+ subscription+', bufferlength='+str(bufferlength)+', push_rate='+str(rate)+', push_policy='+pushpolicy+')')
ret, prof = inP.connect(con_prof)
if ret != RTC.RTC_OK:
print("failed to connect")
continue
# confirm connection
if isConnected(outP, inP) == False:
print("connet() returned RTC_OK, but not connected")
##
# \brief convert data into CDR format
# \param data data to be converted
# \return converted data in CDR format
#
def data2cdr(data):
return cdrMarshal(any.to_any(data).typecode(), data, True)
##
# \brief get class object from class name
# \param fullname class name
# \return class object
#
def classFromString(fullname):
component_path = fullname.split('.')
package_name = component_path[0]
component_path = component_path[1:]
attr = None
while component_path:
class_name = component_path[0]
component_path = component_path[1:]
if attr:
attr = getattr(attr, class_name)
else:
__import__(str(package_name))
attr = getattr(sys.modules[package_name], class_name)
return attr
##
# \brief convert data from CDR format
# \param cdr in CDR format
# \param classname class name of the data
# \return converted data
#
def cdr2data(cdr, classname):
return cdrUnmarshal(any.to_any(classFromString(classname)).typecode(), cdr, True)
connector_list = []
##
# \brief write data to a data port
# \param port reference of data port
# \param data data to be written
# \param tm If disconnect==True, a connection to write data is disconnected
# after this time
# \param disconnect If True, a connection is disconnected after tm and if not,
# the connection must be disconnected by a user
#
def writeDataPort(port, data, tm=1.0, disconnect=True):
global connector_list, orb
connector_name = "writeDataPort"
prof = None
for p in connector_list:
if p["port"]._is_equivalent(port):
if port.get_connector_profile(p["prof"].connector_id).name == connector_name:
prof = p["prof"]
else:
connector_list.remove(p)
if prof is None:
nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any("corba_cdr"))
nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any("Push"))
nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any("flush"))
con_prof = RTC.ConnectorProfile(connector_name, "", [port], [nv1, nv2, nv3])
ret, prof = port.connect(con_prof)
if ret != RTC.RTC_OK:
print("failed to connect")
return None
connector_list.append({"port":port,"prof":prof})
for p in prof.properties:
if p.name == 'dataport.corba_cdr.inport_ior':
ior = any.from_any(p.value)
obj = orb.string_to_object(ior)
inport = obj._narrow(InPortCdr)
cdr = data2cdr(data)
if inport.put(cdr) != OpenRTM.PORT_OK:
print("failed to put")
if disconnect:
time.sleep(tm)
port.disconnect(prof.connector_id)
for p in connector_list:
if prof.connector_id == p["prof"].connector_id:
connector_list.remove(p)
else:
return prof.connector_id
return None
##
# \brief read data from a data port
# \param port reference of data port
# \param timeout timeout[s]
# \return data
#
def readDataPort(port, timeout=1.0, disconnect=True):
global connector_list, orb
connector_name = "readDataPort"
prof = None
for p in connector_list:
if p["port"]._is_equivalent(port):
if port.get_connector_profile(p["prof"].connector_id).name == connector_name:
prof = p["prof"]
else:
connector_list.remove(p)
pprof = port.get_port_profile()
for prop in pprof.properties:
if prop.name == "dataport.data_type":
classname = any.from_any(prop.value)
if prof is None:
nv1 = SDOPackage.NameValue("dataport.interface_type", any.to_any("corba_cdr"))
nv2 = SDOPackage.NameValue("dataport.dataflow_type", any.to_any("Pull"))
nv3 = SDOPackage.NameValue("dataport.subscription_type", any.to_any("flush"))
con_prof = RTC.ConnectorProfile(connector_name, "", [port], [nv1, nv2, nv3])
ret, prof = port.connect(con_prof)
if ret != RTC.RTC_OK:
print("failed to connect")
return None
connector_list.append({"port":port,"prof":prof})
for p in prof.properties:
if p.name == 'dataport.corba_cdr.outport_ior':
ior = any.from_any(p.value)
obj = orb.string_to_object(ior)
outport = obj._narrow(OutPortCdr)
tm = 0
while tm < timeout:
try:
ret, data = outport.get()
if ret == OpenRTM.PORT_OK:
if disconnect:
port.disconnect(prof.connector_id)
for p in connector_list:
if prof.connector_id == p["prof"].connector_id:
connector_list.remove(p)
tokens = classname.split(':')
if len(tokens) == 3: # for 1.1?
classname = tokens[1].replace('/', '.')
return cdr2data(data, classname)
except:
pass
time.sleep(0.1)
tm = tm + 0.1
return None
##
# \brief
#
def deleteAllConnector():
global connector_list
for port in connector_list:
port["port"].disconnect(port["prof"].connector_id)
del connector_list[:]
##
# \brief get a service of RT component
# \param rtc IOR of RT component
# \param port_name port name of the port which provides the service
# \param type_name type name of the service
# \param instance_name name of the service
# \return IOR of the service
#
def findService(rtc, port_name, type_name, instance_name):
if port_name == "":
prof = rtc.ref.get_component_profile()
# print("RTC name:",prof.instance_name)
port_prof = prof.port_profiles
else:
p = rtc.port(port_name)
if p == None:
print("can't find a port named" + port_name)
return None
else:
port_prof = [p.get_port_profile()]
port = None
for pp in port_prof:
# print("name:", pp.name)
ifs = pp.interfaces
for aif in ifs:
#print("IF name:", aif.instance_name)
#print("IF type:", aif.type_name)
if aif.instance_name == instance_name and \
(type_name == "" or aif.type_name == type_name) and \
aif.polarity == PROVIDED:
port = pp.port_ref
if port == None:
print("can't find a service named", instance_name)
return None
con_prof = RTC.ConnectorProfile("noname", "", [port], [])
ret, con_prof = port.connect(con_prof)
ior = any.from_any(con_prof.properties[0].value)
return orb.string_to_object(ior)
##
# \brief update default configuration set
# \param rtc IOR of RT component
# \param nvlist list of pairs of name and value
# \return True if all values are set correctly, False otherwise
#
def setConfiguration(rtc, nvlist):
ret = True
cfg = rtc.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print("configuration set is not found")
return
cfgset = cfgsets[0]
for nv in nvlist:
name = nv[0]
value = nv[1]
found = False
for d in cfgset.configuration_data:
if d.name == name:
d.value = any.to_any(value)
cfg.set_configuration_set_values(cfgset)
found = True
break
if not found:
ret = False
cfg.activate_configuration_set('default')
return ret
##
# \brief get default configuration set
# \param rtc IOR of RT component
# \return default configuration set
#
def getConfiguration(rtc):
cfg = rtc.get_configuration()
cfgsets = cfg.get_configuration_sets()
if len(cfgsets) == 0:
print("configuration set is not found")
return None
ret = {}
for nv in cfgsets[0].configuration_data:
ret[nv.name] = any.from_any(nv.value)
return ret
##
# \brief narrow ior
# \param ior ior
# \param klass class name
# \param package package where the class is defined
#
def narrow(ior, klass, package="OpenHRP"):
return ior._narrow(getattr(sys.modules[package], klass))
##
# \brief check if jython or python
# \return True if jython
#
def isJython():
return sys.version.count("GCC") == 0
if __name__ == '__main__':
initCORBA()