params.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2012, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 
33 import fnmatch
34 import rospy
35 import threading
36 
37 from json import loads, dumps
38 
39 
40 """ Methods to interact with the param server. Values have to be passed
41 as JSON in order to facilitate dynamically typed SRV messages """
42 
43 # rospy parameter server isn't thread-safe
44 param_server_lock = threading.RLock()
45 
46 def set_param(name, value, params_glob):
47  if params_glob and not any(fnmatch.fnmatch(str(name), glob) for glob in params_glob):
48  # If the glob list is not empty and there are no glob matches,
49  # stop the attempt to set the parameter.
50  return
51  # If the glob list is empty (i.e. false) or the parameter matches
52  # one of the glob strings, continue to set the parameter.
53  d = None
54  try:
55  d = loads(value)
56  except ValueError:
57  raise Exception("Due to the type flexibility of the ROS parameter server, the value argument to set_param must be a JSON-formatted string.")
58  with param_server_lock:
59  rospy.set_param(name, d)
60 
61 
62 def get_param(name, default, params_glob):
63  if params_glob and not any(fnmatch.fnmatch(str(name), glob) for glob in params_glob):
64  # If the glob list is not empty and there are no glob matches,
65  # stop the attempt to get the parameter.
66  return
67  # If the glob list is empty (i.e. false) or the parameter matches
68  # one of the glob strings, continue to get the parameter.
69  d = None
70  if default is not "":
71  try:
72  d = loads(default)
73  except ValueError:
74  d = default
75  with param_server_lock:
76  value = rospy.get_param(name, d)
77  return dumps(value)
78 
79 def has_param(name, params_glob):
80  if params_glob and not any(fnmatch.fnmatch(str(name), glob) for glob in params_glob):
81  # If the glob list is not empty and there are no glob matches,
82  # stop the attempt to set the parameter.
83  return False
84  # If the glob list is empty (i.e. false) or the parameter matches
85  # one of the glob strings, check whether the parameter exists.
86  with param_server_lock:
87  return rospy.has_param(name)
88 
89 def delete_param(name, params_glob):
90  if params_glob and not any(fnmatch.fnmatch(str(name), glob) for glob in params_glob):
91  # If the glob list is not empty and there are no glob matches,
92  # stop the attempt to delete the parameter.
93  return
94  # If the glob list is empty (i.e. false) or the parameter matches
95  # one of the glob strings, continue to delete the parameter.
96  if has_param(name, params_glob):
97  with param_server_lock:
98  rospy.delete_param(name)
99 
100 def search_param(name, params_glob):
101  if params_glob and not any(fnmatch.fnmatch(str(name), glob) for glob in params_glob):
102  # If the glob list is not empty and there are no glob matches,
103  # stop the attempt to find the parameter.
104  return None
105  # If the glob list is empty (i.e. false) or the parameter matches
106  # one of the glob strings, continue to find the parameter.
107  return rospy.search_param(name)
108 
109 def get_param_names(params_glob):
110  with param_server_lock:
111  if params_glob:
112  # If there is a parameter glob, filter by it.
113  return filter(lambda x: any(fnmatch.fnmatch(str(x), glob) for glob in params_glob), rospy.get_param_names())
114  else:
115  # If there is no parameter glob, don't filter.
116  return rospy.get_param_names()
117 
def has_param(name, params_glob)
Definition: params.py:79
def set_param(name, value, params_glob)
Definition: params.py:46
def delete_param(name, params_glob)
Definition: params.py:89
def get_param_names(params_glob)
Definition: params.py:109
def get_param(name, default, params_glob)
Definition: params.py:62
def search_param(name, params_glob)
Definition: params.py:100


rosapi
Author(s): Jonathan Mace
autogenerated on Fri May 10 2019 02:17:04