29 from __future__
import absolute_import
31 from functools
import partial
40 from requests.adapters
import HTTPAdapter
41 from requests.packages.urllib3.util.retry
import Retry
45 from .message_converter
import convert_dictionary_to_ros_message, convert_ros_message_to_dictionary
49 status_forcelist=[429],
52 A requests session that will retry on TOO_MANY_REQUESTS.
54 E.g. replace requests.get() with requests_retry_session().get()
56 session = session
or requests.Session()
61 backoff_factor=backoff_factor,
62 status_forcelist=status_forcelist,
64 adapter = HTTPAdapter(max_retries=retry)
65 session.mount(
'http://', adapter)
66 session.mount(
'https://', adapter)
72 def __init__(self, rest_name, ignored_parameters=[]):
78 rospy.init_node(rest_name +
'_client', log_level=rospy.INFO)
80 self.
host = rospy.get_param(
'~host',
'')
82 rospy.logerr(
'host is not set')
85 self.
pipeline = rospy.get_param(
'~pipeline', 0)
95 if res.status_code != 200:
96 rospy.logerr(
"Getting parameters failed with status code: %d", res.status_code)
99 except Exception
as e:
108 rospy.logdebug(
"set parameters response: %s", json.dumps(j, indent=2))
109 if 'return_code' in j
and j[
'return_code'][
'value'] != 0:
110 rospy.logwarn(
"Setting parameter failed: %s", j[
'return_code'][
'message'])
112 if res.status_code != 200:
113 rospy.logerr(
"Setting parameters failed with status code: %d", res.status_code)
116 except Exception
as e:
124 def enum_method_from_param(p):
125 if p[
'type'] !=
'string':
127 enum_matches = re.findall(
r'.*\[(?P<enum>.+)\].*', p[
'description'])
130 enum_names = [str(e.strip())
for e
in enum_matches[0].split(
',')]
131 enum_list = [self.
ddr.const(n,
'str', n, n)
for n
in enum_names]
132 return self.
ddr.enum(enum_list, p[
'name'] +
'_enum')
134 for p
in rest_params:
136 edit_method = enum_method_from_param(p)
137 if p[
'type'] ==
'int32':
138 self.
ddr.add(p[
'name'],
'int', level, p[
'description'], p[
'default'], p[
'min'], p[
'max'])
139 elif p[
'type'] ==
'float64':
140 self.
ddr.add(p[
'name'],
'double', level, p[
'description'], p[
'default'], p[
'min'], p[
'max'])
141 elif p[
'type'] ==
'string':
142 self.
ddr.add(p[
'name'],
'str', level, p[
'description'], str(p[
'default']), edit_method=edit_method)
143 elif p[
'type'] ==
'bool':
144 self.
ddr.add(p[
'name'],
'bool', level, p[
'description'], p[
'default'])
146 rospy.logwarn(
"Unsupported parameter type: %s", p[
'type'])
151 rospy.logdebug(
"Received reconf call: " + str(config))
152 new_rest_params = [{
'name': n,
'value': config[n]}
for n
in self.
ddr.get_variable_names()
if n
in config]
155 for p
in returned_params:
156 if p[
'name']
not in config:
157 rospy.logerr(
"param %s not in config", p[
'name'])
159 config[p[
'name']] = p[
'value']
165 if request
is not None:
167 args = convert_ros_message_to_dictionary(request)
168 rospy.logdebug(
'calling {} with args: {}'.format(name, args))
174 rospy.logdebug(
"{} rest response: {}".format(name, json.dumps(j, indent=2)))
175 rc = j[
'response'].get(
'return_code')
176 if rc
is not None and rc[
'value'] < 0:
177 rospy.logwarn(
"service {} returned an error: [{}] {}".format(name, rc[
'value'], rc[
'message']))
180 if srv_type
is not None:
181 response = convert_dictionary_to_ros_message(srv_type._response_class(), j[
'response'], strict_mode=
False)
183 response = j[
'response']
184 except Exception
as e:
186 if srv_type
is not None:
187 response = srv_type._response_class()
188 if hasattr(response,
'return_code'):
189 response.return_code.value = -1000
190 response.return_code.message = str(e)
194 """create a service and inject the REST-API service name"""
195 srv = rospy.Service(rospy.get_name() +
"/" + srv_name, srv_type, partial(callback, srv_name, srv_type))