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