1
2 import threading
3 import copy
4
5 import smach
6
7 __all__ = ['UserData','Remapper']
8
10 """SMACH user data structure."""
12 self._data = {}
13 self._locks = {}
14 self.__initialized = True
15
16 - def update(self, other_userdata):
17 """Combine this userdata struct with another.
18 This overwrites duplicate keys with values from C{other_userdata}.
19 """
20
21 self._data.update(other_userdata._data)
22
24 ud = UserData()
25 reverse_remapping = dict([(v,k) for (k,v) in remapping.iteritems()])
26 if len(reverse_remapping) != len(remapping):
27 smach.logerr("SMACH userdata remapping is not one-to-one: " + str(remapping))
28 for k in keys:
29 rmk = k
30 if k in reverse_remapping:
31 rmk = reverse_remapping[k]
32 ud[rmk] = copy.copy(self[k])
33 return ud
34
35 - def merge(self, ud, keys, remapping):
36 for k in keys:
37 rmk = k
38 if k in remapping:
39 rmk = remapping[k]
40 self[rmk] = copy.copy(ud[k])
41
44
46 self._data[key] = item
47
49 return self._data.keys()
50
52 return key in self._data
53
55 """Overload getattr to be thread safe."""
56 if name[0] == '_':
57 return object.__getattr__(self, name)
58 if not name in self._locks.keys():
59 self._locks[name] = threading.Lock()
60
61 try:
62 with self._locks[name]:
63 temp = self._data[name]
64 except:
65 smach.logerr("Userdata key '%s' not available. Available keys are: %s" % (name, self._data.keys()))
66 raise KeyError()
67
68 return temp
69
71 """Overload setattr to be thread safe."""
72
73 if name[0] == '_' or not self.__dict__.has_key('_UserData__initialized'):
74 return object.__setattr__(self, name, value)
75
76 if not name in self._locks.keys():
77 self._locks[name] = threading.Lock()
78
79 self._locks[name].acquire()
80 self._data[name] = value
81 self._locks[name].release()
82
83
85 """Get a const reference to an object if it has "user-defined" attributes."""
86 if hasattr(obj,'__dict__'):
87 smach.logdebug("Making const '%s'" % str(obj))
88 return Const(obj)
89 else:
90 return obj
91
93 """Wrapper that treats "user-defined" fields as immutable.
94
95 This wrapper class is used when user data keys are specified as input keys,
96 but not as output keys.
97 """
99 smach.logdebug("Making const '%s'" % str(obj))
100 self._obj = obj
101 self.__initialized = True
102
104 smach.logdebug("Getting '%s' from const wrapper." % name)
105 attr = getattr(self._obj,name)
106 return get_const(attr)
107
109 smach.logdebug("Getting '%s' from const wrapper." % name)
110 attr = self._obj[name]
111 return get_const(attr)
112
114 if not self.__dict__.has_key('_const__initialized'):
115 return object.__setattr__(self, name, value)
116 smach.logerr("Attempting to set '%s' but this member is read-only." % name)
117 raise TypeError()
118
120 smach.logerr("Attempting to delete '%s' but this member is read-only." % name)
121 raise TypeError()
122
124 """Key-remapping proxy to a SMACH userdata structure."""
125 - def __init__(self, ud, input_keys=[], output_keys=[], remapping={}):
126 self._ud = ud
127 self._input = input_keys
128 self._output = output_keys
129 self._map = remapping
130 self.__initialized = True
131
133 """Return either the key or it's remapped value."""
134 if key in self._map:
135 return self._map[key]
136 return key
137
138 - def update(self, other_userdata):
139 self._ud.updatea(other_userdata)
140
142 if key not in self._input:
143 raise smach.InvalidUserCodeError("Reading from SMACH userdata key '%s' but the only keys that were declared as input to this state were: %s. This key needs to be declaread as input to this state. " % (key, self._input))
144 if key not in self._output:
145 return get_const(self._ud.__getitem__(self._remap(key)))
146 return self._ud.__getitem__(self._remap(key))
147
149 if key not in self._output:
150 smach.logerr("Writing to SMACH userdata key '%s' but the only keys that were declared as output from this state were: %s." % (key, self._output))
151 return
152 self._ud.__setitem__(self._remap(key),item)
153
155 return [self._remap(key) for key in self._ud.keys() if key in self._input]
156
158 if key in self._input:
159 return self._remap(key) in self._ud
160 else:
161 return False
162
164 if name[0] == '_':
165 return object.__getattr__(self, name)
166 if name not in self._input:
167 raise smach.InvalidUserCodeError("Reading from SMACH userdata key '%s' but the only keys that were declared as input to this state were: %s. This key needs to be declaread as input to this state. " % (name, self._input))
168 if name not in self._output:
169 return get_const(getattr(self._ud, self._remap(name)))
170 return getattr(self._ud, self._remap(name))
171
173 if name[0] == '_' or not self.__dict__.has_key('_Remapper__initialized'):
174 return object.__setattr__(self, name, value)
175 if name not in self._output:
176 smach.logerr("Writing to SMACH userdata key '%s' but the only keys that were declared as output from this state were: %s." % (name, self._output))
177 return None
178 setattr(self._ud, self._remap(name), value)
179