Package rosgraph :: Module xmlrpc
[frames] | no frames]

Source Code for Module rosgraph.xmlrpc

  1  # Software License Agreement (BSD License) 
  2  # 
  3  # Copyright (c) 2008, 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  # Revision $Id: xmlrpc.py 15336 2011-11-07 20:43:00Z kwc $ 
 34   
 35  from __future__ import print_function 
 36   
 37  """ 
 38  Common XML-RPC for higher-level libraries running XML-RPC libraries in 
 39  ROS. In particular, this library provides common handling for URI 
 40  calculation based on ROS environment variables. 
 41   
 42  The common entry point for most libraries is the L{XmlRpcNode} class. 
 43  """ 
 44   
 45  import errno 
 46  import logging 
 47  import platform 
 48  import select 
 49  import socket 
 50   
 51  try: 
 52      import _thread 
 53  except ImportError: 
 54      import thread as _thread 
 55   
 56  import traceback 
 57   
 58  try: 
 59      from xmlrpc.server import SimpleXMLRPCServer, SimpleXMLRPCRequestHandler #Python 3.x 
 60  except ImportError: 
 61      from SimpleXMLRPCServer import SimpleXMLRPCServer #Python 2.x 
 62      from SimpleXMLRPCServer import SimpleXMLRPCRequestHandler #Python 2.x 
 63   
 64  try: 
 65      import socketserver 
 66  except ImportError: 
 67      import SocketServer as socketserver 
 68   
 69  import rosgraph.network 
 70   
71 -def isstring(s):
72 """Small helper version to check an object is a string in a way that works 73 for both Python 2 and 3 74 """ 75 try: 76 return isinstance(s, basestring) 77 except NameError: 78 return isinstance(s, str)
79 80
81 -def _support_http_1_1():
82 """ 83 Determine whether HTTP 1.1 should be enabled for XMLRPC communications. 84 85 This will be true on non-Linux systems, and on Linux kernels at least as 86 new as 4.16. Linux kernels 4.15 and older cause significant performance 87 degradation in the roscore when using HTTP 1.1 88 """ 89 if platform.system() != 'Linux': 90 return True 91 minimum_supported_major, minimum_supported_minor = (4, 16) 92 release = platform.release().split('.') 93 platform_major = int(release[0]) 94 platform_minor = int(release[1]) 95 if platform_major < minimum_supported_major: 96 return False 97 if (platform_major == minimum_supported_major and 98 platform_minor < minimum_supported_minor): 99 return False 100 return True
101 102
103 -class SilenceableXMLRPCRequestHandler(SimpleXMLRPCRequestHandler):
104 if _support_http_1_1(): 105 protocol_version = 'HTTP/1.1' 106
107 - def log_message(self, format, *args):
108 if 0: 109 SimpleXMLRPCRequestHandler.log_message(self, format, *args)
110
111 -class ThreadingXMLRPCServer(socketserver.ThreadingMixIn, SimpleXMLRPCServer):
112 """ 113 Adds ThreadingMixin to SimpleXMLRPCServer to support multiple concurrent 114 requests via threading. Also makes logging toggleable. 115 """ 116 117 daemon_threads = True 118
119 - def __init__(self, addr, log_requests=1):
120 """ 121 Overrides SimpleXMLRPCServer to set option to allow_reuse_address. 122 """ 123 # allow_reuse_address defaults to False in Python 2.4. We set it 124 # to True to allow quick restart on the same port. This is equivalent 125 # to calling setsockopt(SOL_SOCKET,SO_REUSEADDR,1) 126 self.allow_reuse_address = True 127 # Increase request_queue_size to handle issues with many simultaneous 128 # connections in OSX 10.11 129 self.request_queue_size = min(socket.SOMAXCONN, 128) 130 if rosgraph.network.use_ipv6(): 131 logger = logging.getLogger('xmlrpc') 132 # The XMLRPC library does not support IPv6 out of the box 133 # We have to monipulate private members and duplicate 134 # code from the constructor. 135 # TODO IPV6: Get this into SimpleXMLRPCServer 136 SimpleXMLRPCServer.__init__(self, addr, SilenceableXMLRPCRequestHandler, log_requests, bind_and_activate=False) 137 self.address_family = socket.AF_INET6 138 self.socket = socket.socket(self.address_family, self.socket_type) 139 logger.info('binding ipv6 xmlrpc socket to' + str(addr)) 140 # TODO: set IPV6_V6ONLY to 0: 141 # self.socket.setsockopt(socket.IPPROTO_IPV6, socket.IPV6_V6ONLY, 0) 142 self.server_bind() 143 self.server_activate() 144 logger.info('bound to ' + str(self.socket.getsockname()[0:2])) 145 else: 146 SimpleXMLRPCServer.__init__(self, addr, SilenceableXMLRPCRequestHandler, log_requests)
147
148 - def handle_error(self, request, client_address):
149 """ 150 override ThreadingMixin, which sends errors to stderr 151 """ 152 if logging and traceback: 153 logger = logging.getLogger('xmlrpc') 154 if logger: 155 logger.error(traceback.format_exc())
156 157 158 # ForkingMixIn and the Forking classes mentioned below are only available on POSIX platforms. 159 if hasattr(socketserver, "ForkingMixIn"):
160 - class ForkingXMLRPCServer(socketserver.ForkingMixIn, SimpleXMLRPCServer):
161 """ 162 Adds ThreadingMixin to SimpleXMLRPCServer to support multiple concurrent 163 requests via forking. Also makes logging toggleable. 164 """
165 - def __init__(self, addr, request_handler=SilenceableXMLRPCRequestHandler, log_requests=1):
166 SimpleXMLRPCServer.__init__(self, addr, request_handler, log_requests)
167 168
169 -class XmlRpcHandler(object):
170 """ 171 Base handler API for handlers used with XmlRpcNode. Public methods will be 172 exported as XML RPC methods. 173 """ 174
175 - def _ready(self, uri):
176 """ 177 callback into handler to inform it of XML-RPC URI 178 """ 179 pass
180
181 - def _shutdown(self, reason):
182 """ 183 callback into handler to inform it of shutdown 184 """ 185 pass
186
187 -class XmlRpcNode(object):
188 """ 189 Generic XML-RPC node. Handles the additional complexity of binding 190 an XML-RPC server to an arbitrary port. 191 XmlRpcNode is initialized when the uri field has a value. 192 """ 193
194 - def __init__(self, port=0, rpc_handler=None, on_run_error=None):
195 """ 196 XML RPC Node constructor 197 :param port: port to use for starting XML-RPC API. Set to 0 or omit to bind to any available port, ``int`` 198 :param rpc_handler: XML-RPC API handler for node, `XmlRpcHandler` 199 :param on_run_error: function to invoke if server.run() throws 200 Exception. Server always terminates if run() throws, but this 201 enables cleanup routines to be invoked if server goes down, as 202 well as include additional debugging. ``fn(Exception)`` 203 """ 204 super(XmlRpcNode, self).__init__() 205 206 self.handler = rpc_handler 207 self.uri = None # initialize the property now so it can be tested against, will be filled in later 208 self.server = None 209 if port and isstring(port): 210 port = int(port) 211 self.port = port 212 self.is_shutdown = False 213 self.on_run_error = on_run_error
214
215 - def shutdown(self, reason):
216 """ 217 Terminate i/o connections for this server. 218 219 :param reason: human-readable debug string, ``str`` 220 """ 221 self.is_shutdown = True 222 if self.server: 223 server = self.server 224 handler = self.handler 225 self.handler = self.server = self.port = self.uri = None 226 if handler: 227 handler._shutdown(reason) 228 if server: 229 server.socket.close() 230 server.server_close()
231
232 - def start(self):
233 """ 234 Initiate a thread to run the XML RPC server. Uses thread.start_new_thread. 235 """ 236 _thread.start_new_thread(self.run, ())
237
238 - def set_uri(self, uri):
239 """ 240 Sets the XML-RPC URI. Defined as a separate method as a hood 241 for subclasses to bootstrap initialization. Should not be called externally. 242 243 :param uri: XMLRPC URI, ``str`` 244 """ 245 self.uri = uri
246
247 - def run(self):
248 try: 249 self._run() 250 except Exception as e: 251 if self.is_shutdown: 252 pass 253 elif self.on_run_error is not None: 254 self.on_run_error(e) 255 else: 256 raise
257 258 # separated out for easier testing
259 - def _run_init(self):
260 logger = logging.getLogger('xmlrpc') 261 try: 262 log_requests = 0 263 port = self.port or 0 #0 = any 264 265 bind_address = rosgraph.network.get_bind_address() 266 logger.info("XML-RPC server binding to %s:%d" % (bind_address, port)) 267 268 self.server = ThreadingXMLRPCServer((bind_address, port), log_requests) 269 self.port = self.server.server_address[1] #set the port to whatever server bound to 270 if not self.port: 271 self.port = self.server.socket.getsockname()[1] #Python 2.4 272 273 assert self.port, "Unable to retrieve local address binding" 274 275 # #528: semi-complicated logic for determining XML-RPC URI 276 # - if ROS_IP/ROS_HOSTNAME is set, use that address 277 # - if the hostname returns a non-localhost value, use that 278 # - use whatever rosgraph.network.get_local_address() returns 279 uri = None 280 override = rosgraph.network.get_address_override() 281 if override: 282 uri = 'http://%s:%s/'%(override, self.port) 283 else: 284 try: 285 hostname = socket.gethostname() 286 if hostname and not hostname == 'localhost' and not hostname.startswith('127.') and hostname != '::': 287 uri = 'http://%s:%s/'%(hostname, self.port) 288 except: 289 pass 290 if not uri: 291 uri = 'http://%s:%s/'%(rosgraph.network.get_local_address(), self.port) 292 self.set_uri(uri) 293 294 logger.info("Started XML-RPC server [%s]", self.uri) 295 296 self.server.register_multicall_functions() 297 self.server.register_instance(self.handler) 298 299 except socket.error as e: 300 if e.errno == errno.EADDRINUSE: 301 msg = "ERROR: Unable to start XML-RPC server, port %s is already in use"%self.port 302 else: 303 msg = "ERROR: Unable to start XML-RPC server: %s" % e.strerror 304 logger.error(msg) 305 print(msg) 306 raise #let higher level catch this 307 308 if self.handler is not None: 309 self.handler._ready(self.uri) 310 logger.info("xml rpc node: starting XML-RPC server")
311
312 - def _run(self):
313 """ 314 Main processing thread body. 315 :raises: :exc:`socket.error` If server cannot bind 316 317 """ 318 self._run_init() 319 while not self.is_shutdown: 320 try: 321 self.server.serve_forever() 322 except (IOError, select.error) as e: 323 # check for interrupted call, which can occur if we're 324 # embedded in a program using signals. All other 325 # exceptions break _run. 326 if self.is_shutdown: 327 pass 328 elif e.errno != errno.EINTR: 329 self.is_shutdown = True 330 logging.getLogger('xmlrpc').error("serve forever IOError: %s, %s"%(e.errno, e.strerror))
331