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  from threading import RLock 
 34   
 35  from rosgraph.names import ns_join, GLOBALNS, SEP, is_global, is_private, canonicalize_name 
 36   
 38      """ 
 39      helper recursive routine for getParamNames() 
 40      @param names: list of param names to append to 
 41      @type  names: [str] 
 42      @param d: parameter tree node 
 43      @type  d: dict 
 44      @param key: parameter key for tree node d 
 45      @type  key: str 
 46      """ 
 47       
 48       
 49      for k,v in d.items(): 
 50          if type(v) == dict: 
 51              _get_param_names(names, ns_join(key, k), v) 
 52          else: 
 53              names.append(ns_join(key, k)) 
  54   
 56       
 58          """ 
 59          ctor. 
 60          @param subscribers: parameter subscribers 
 61          @type  subscribers: Registrations 
 62          """ 
 63          self.lock = RLock() 
 64          self.parameters = {} 
 65          self.reg_manager = reg_manager 
  66   
 68          """ 
 69          Get list of all parameter names stored on this server. 
 70   
 71          @return: [code, statusMessage, parameterNameList] 
 72          @rtype: [int, str, [str]] 
 73          """ 
 74          try: 
 75              self.lock.acquire() 
 76              param_names = [] 
 77              _get_param_names(param_names, '/', self.parameters) 
 78          finally: 
 79              self.lock.release() 
 80          return param_names 
  81           
 83          """ 
 84          Search for matching parameter key for search param 
 85          key. Search for key starts at ns and proceeds upwards to 
 86          the root. As such, search_param should only be called with a 
 87          relative parameter name. 
 88   
 89          search_param's behavior is to search for the first partial match. 
 90          For example, imagine that there are two 'robot_description' parameters: 
 91   
 92           - /robot_description 
 93           -   /robot_description/arm 
 94           -   /robot_description/base 
 95   
 96           - /pr2/robot_description 
 97           -   /pr2/robot_description/base 
 98   
 99          If I start in the namespace /pr2/foo and search for 
100          'robot_description', search_param will match 
101          /pr2/robot_description. If I search for 'robot_description/arm' 
102          it will return /pr2/robot_description/arm, even though that 
103          parameter does not exist (yet). 
104   
105          @param ns: namespace to begin search from. 
106          @type  ns: str 
107          @param key: Parameter key.  
108          @type  key: str 
109          @return: key of matching parameter or None if no matching 
110          parameter. 
111          @rtype: str 
112          """ 
113          if not key or is_private(key): 
114              raise ValueError("invalid key") 
115          if not is_global(ns): 
116              raise ValueError("namespace must be global")             
117          if is_global(key): 
118              if self.has_param(key): 
119                  return key 
120              else: 
121                  return None 
122   
123           
124           
125   
126           
127          key_namespaces = [x for x in key.split(SEP) if x] 
128          key_ns = key_namespaces[0] 
129   
130           
131           
132          search_key = ns_join(ns, key_ns) 
133          if self.has_param(search_key): 
134               
135              return ns_join(ns, key)  
136           
137          namespaces = [x for x in ns.split(SEP) if x] 
138          for i in range(1, len(namespaces)+1): 
139              search_key = SEP + SEP.join(namespaces[0:-i] + [key_ns]) 
140              if self.has_param(search_key): 
141                   
142                   
143                  full_key = SEP + SEP.join(namespaces[0:-i] + [key])  
144                  return full_key 
145          return None 
 146   
148          """ 
149          Get the parameter in the parameter dictionary. 
150   
151          @param key: parameter key 
152          @type  key: str 
153          @return: parameter value 
154          """ 
155          try: 
156              self.lock.acquire() 
157              val = self.parameters 
158              if key != GLOBALNS: 
159                   
160                  namespaces = [x for x in key.split(SEP)[1:] if x] 
161                  for ns in namespaces: 
162                      if not type(val) == dict: 
163                          raise KeyError(val) 
164                      val = val[ns] 
165              return val 
166          finally: 
167              self.lock.release() 
 168       
169 -    def set_param(self, key, value, notify_task=None): 
 170          """ 
171          Set the parameter in the parameter dictionary. 
172   
173          @param key: parameter key 
174          @type  key: str 
175          @param value: parameter value 
176          @param notify_task: function to call with 
177          subscriber updates. updates is of the form 
178          [(subscribers, param_key, param_value)*]. The empty dictionary 
179          represents an unset parameter. 
180          @type  notify_task: fn(updates) 
181          """ 
182          try: 
183              self.lock.acquire() 
184              if key == GLOBALNS: 
185                  if type(value) != dict: 
186                      raise TypeError("cannot set root of parameter tree to non-dictionary") 
187                  self.parameters = value 
188              else: 
189                  namespaces = [x for x in key.split(SEP) if x] 
190                   
191                  value_key = namespaces[-1] 
192                  namespaces = namespaces[:-1] 
193                  d = self.parameters 
194                   
195                  for ns in namespaces: 
196                      if not ns in d: 
197                          new_d = {} 
198                          d[ns] = new_d 
199                          d = new_d 
200                      else: 
201                          val = d[ns] 
202                           
203                          if type(val) != dict: 
204                              d[ns] = val = {} 
205                          d = val 
206   
207                  d[value_key] = value 
208   
209               
210              if notify_task: 
211                  updates = compute_param_updates(self.reg_manager.param_subscribers, key, value) 
212                  if updates: 
213                      notify_task(updates) 
214          finally: 
215              self.lock.release() 
 216   
217   
219          """ 
220          @param key: parameter key 
221          @type  key: str 
222          @param registration_args: additional args to pass to 
223          subscribers.register. First parameter is always the parameter 
224          key. 
225          @type  registration_args: tuple 
226          """ 
227          if key != SEP: 
228              key = canonicalize_name(key) + SEP 
229          try: 
230              self.lock.acquire() 
231               
232              try: 
233                  val = self.get_param(key) 
234              except KeyError: 
235                   
236                  val = {} 
237              self.reg_manager.register_param_subscriber(key, *registration_args) 
238              return val 
239          finally: 
240              self.lock.release() 
 241               
242   
244          """ 
245          @param key str: parameter key 
246          @type  key: str 
247          @param unregistration_args: additional args to pass to 
248          subscribers.unregister. i.e. unregister will be called with 
249          (key, *unregistration_args) 
250          @type  unregistration_args: tuple 
251          @return: return value of subscribers.unregister() 
252          """ 
253          if key != SEP: 
254              key = canonicalize_name(key) + SEP 
255          return self.reg_manager.unregister_param_subscriber(key, *unregistration_args) 
 256   
258          """ 
259          Delete the parameter in the parameter dictionary. 
260          @param key str: parameter key 
261          @param notify_task fn(updates): function to call with 
262          subscriber updates. updates is of the form 
263          [(subscribers, param_key, param_value)*]. The empty dictionary 
264          represents an unset parameter. 
265          """ 
266          try: 
267              self.lock.acquire() 
268              if key == GLOBALNS: 
269                  raise KeyError("cannot delete root of parameter tree") 
270              else: 
271                   
272                  namespaces = [x for x in key.split(SEP) if x] 
273                   
274                  value_key = namespaces[-1] 
275                  namespaces = namespaces[:-1] 
276                  d = self.parameters 
277                   
278                  for ns in namespaces: 
279                      if type(d) != dict or not ns in d: 
280                          raise KeyError(key) 
281                      else: 
282                          d = d[ns] 
283   
284                  if not value_key in d: 
285                      raise KeyError(key) 
286                  else: 
287                      del d[value_key] 
288                       
289                   
290                  if notify_task: 
291                      updates = compute_param_updates(self.reg_manager.param_subscribers, key, {}) 
292                      if updates: 
293                          notify_task(updates) 
294          finally: 
295              self.lock.release() 
 296       
298          """ 
299          Test for parameter existence 
300   
301          @param key: parameter key 
302          @type  key: str 
303          @return: True if parameter set, False otherwise 
304          @rtype: bool 
305          """ 
306          try: 
307               
308               
309              self.get_param(key) 
310              return True 
311          except KeyError: 
312              return False 
  313       
315      """ 
316      Compute which subscribers should be notified based on the parameter update 
317      @param param_key: key of updated parameter 
318      @type  param_key: str 
319      @param param_value: value of updated parameter 
320      @param all_keys: (internal use only) list of parameter keys 
321          to append to for recursive calls. 
322      @type  all_keys: [str] 
323      @return: list of parameter keys. All keys will be canonicalized with trailing slash. 
324      @rtype: [str] 
325      """ 
326      if all_keys is None: 
327          all_keys = [] 
328      for k, v in param_value.items(): 
329          new_k = ns_join(param_key, k) + SEP  
330          all_keys.append(new_k) 
331          if type(v) == dict: 
332              _compute_all_keys(new_k, v, all_keys) 
333      return all_keys 
 334   
336      """ 
337      Compute subscribers that should be notified based on the parameter update 
338      @param subscribers: parameter subscribers 
339      @type  subscribers: Registrations 
340      @param param_key: parameter key 
341      @type  param_key: str 
342      @param param_value: parameter value 
343      @type  param_value: str 
344      """ 
345       
346       
347   
348      if not subscribers: 
349          return [] 
350       
351       
352       
353      if param_key != SEP: 
354          param_key = canonicalize_name(param_key) + SEP     
355   
356       
357      if type(param_value) == dict: 
358          all_keys = _compute_all_keys(param_key, param_value) 
359      else: 
360          all_keys = None 
361           
362      updates = [] 
363       
364       
365      for sub_key in subscribers.iterkeys(): 
366          ns_key = sub_key 
367          if ns_key[-1] != SEP: 
368              ns_key = sub_key + SEP 
369          if param_key.startswith(ns_key): 
370              node_apis = subscribers[sub_key] 
371              updates.append((node_apis, param_key, param_value)) 
372          elif all_keys is not None and ns_key.startswith(param_key) \ 
373               and not sub_key in all_keys: 
374               
375              node_apis = subscribers[sub_key] 
376              updates.append((node_apis, sub_key, {})) 
377   
378       
379      if all_keys is not None: 
380           
381          for key in all_keys: 
382              if key in subscribers: 
383                   
384                  sub_key = key[len(param_key):] 
385                  namespaces = [x for x in sub_key.split(SEP) if x] 
386                  val = param_value 
387                  for ns in namespaces: 
388                      val = val[ns] 
389   
390                  updates.append((subscribers[key], key, val)) 
391   
392      return updates 
 393