Package roslaunch :: Module server
[frames] | no frames]

Source Code for Module roslaunch.server

  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$ 
 34   
 35  from __future__ import print_function 
 36   
 37  """ 
 38  XML-RPC servers for parent and children 
 39   
 40  Following typical XmlRpcNode code, code is divided into: 
 41   
 42   a) Handlers: these actually define and execute the XML-RPC API 
 43   b) Nodes: these run the XML-RPC server 
 44   
 45  In this code you'll find 'Parent' and 'Child' code. The parent node 
 46  is the original roslaunch process. The child nodes are the child 
 47  processes it launches in order to handle remote launching (or 
 48  execution as a different user). 
 49  """ 
 50   
 51  import errno 
 52  import logging 
 53  import os 
 54  import socket 
 55  import sys 
 56  import time 
 57  import traceback 
 58  try: 
 59      from urllib.parse import urlparse 
 60  except ImportError: 
 61      from urlparse import urlparse 
 62  try: 
 63      from xmlrpc.client import ServerProxy 
 64  except ImportError: 
 65      from xmlrpclib import ServerProxy 
 66   
 67  import rosgraph.network as network 
 68  import rosgraph.xmlrpc as xmlrpc 
 69   
 70  import roslaunch.config  
 71  from roslaunch.pmon import ProcessListener, Process 
 72  import roslaunch.xmlloader 
 73   
 74  from roslaunch.launch import ROSLaunchRunner 
 75  from roslaunch.core import RLException, \ 
 76       add_printlog_handler, add_printerrlog_handler, printlog, printerrlog, printlog_bold 
 77   
 78  #For using Log message level constants 
 79  from rosgraph_msgs.msg import Log 
 80   
 81  # interface class so that we don't have circular deps 
82 -class ChildROSLaunchProcess(Process):
83 """ 84 API for remote roslaunch processes 85 """
86 - def __init__(self, name, args, env):
87 super(ChildROSLaunchProcess, self).__init__('roslaunch', name, args, env, False) 88 self.uri = None
89
90 - def set_uri(self, uri):
91 self.uri = uri
92
93 -class ROSLaunchBaseHandler(xmlrpc.XmlRpcHandler):
94 """ 95 Common XML-RPC API for the roslaunch server and child node 96 """
97 - def __init__(self, pm):
98 self.pm = pm 99 self.logger = logging.getLogger('roslaunch.server') 100 if self.pm is None: 101 raise RLException("cannot create xmlrpc handler: pm is not initialized")
102 103 #TODO: kill process, restart (with optional prefix). list active, list dead. CPU usage 104
105 - def list_processes(self):
106 """ 107 @return: code, msg, process list. 108 Process list is two lists, where first list of 109 active process names along with the number of times that 110 process has been spawned. Second list contains dead process 111 names and their spawn count. 112 @rtype: int, str, [[(str, int),], [(str,int),]] 113 """ 114 return 1, "processes on parent machine", self.pm.get_process_names_with_spawn_count()
115
116 - def process_info(self, process_name):
117 """ 118 @return: dictionary of metadata about process. Keys vary by implementation 119 @rtype: int, str, dict 120 """ 121 p = self.pm.get_process(process_name) 122 if p is None: 123 return -1, "no process by that name", {} 124 else: 125 return 1, "process info", p.get_info()
126
127 - def get_pid(self):
128 """ 129 @return: code, msg, pid 130 @rtype: int, str, int 131 """ 132 133 pid = os.getpid() 134 return 1, str(pid), pid
135
136 - def get_node_names(self):
137 """ 138 @return: code, msg, list of node names 139 @rtype: int, str, [str] 140 """ 141 if self.pm is None: 142 return 0, "uninitialized", [] 143 return 1, "node names", self.pm.get_active_names()
144
145 - def _shutdown(self, reason):
146 """ 147 xmlrpc.XmlRpcHandler API: inform handler of shutdown 148 @param reason: human-readable shutdown reason 149 @type reason: str 150 """ 151 return 1, '', 1
152 153 154 # Uses camel-case network-API naming conventions
155 -class ROSLaunchParentHandler(ROSLaunchBaseHandler):
156 """ 157 XML-RPC API for the roslaunch server node 158 """ 159
160 - def __init__(self, pm, child_processes, listeners):
161 """ 162 @param child_processes: Map of remote processes so that server can update processes 163 with information as children register. Handler will not modify 164 keys. 165 @type child_processes: {name : ChildROSLaunchProcess}. 166 @param listeners [ProcessListener]: list of 167 listeners to notify when process_died events occur. 168 """ 169 super(ROSLaunchParentHandler, self).__init__(pm) 170 self.child_processes = child_processes 171 self.listeners = listeners
172
173 - def register(self, client, uri):
174 """ 175 Registration callback from newly launched roslaunch clients 176 @param client: name of client 177 @type client: str 178 @param uri: XML-RPC URI of client 179 @type uri: str 180 @return: code, msg, ignore 181 @rtype: int, str, int 182 """ 183 if client not in self.child_processes: 184 self.logger.error("Unknown child [%s] registered with server", client) 185 return -1, "unknown child [%s]"%client, 0 186 else: 187 self.logger.info("child [%s] registered with server, uri[%s]", client, uri) 188 self.child_processes[client].set_uri(uri) 189 return 1, "registered", 1
190
191 - def list_children(self):
192 """ 193 List the roslaunch child processes. 194 @return int, str, [str]: code, msg, list of the roslaunch children URIS 195 """ 196 return 1, 'roslaunch children', [v.uri for v in self.child_processes.values() if v.uri is not None]
197
198 - def process_died(self, process_name, exit_code):
199 """ 200 Inform roslaunch server that a remote process has died 201 @param process_name: name of process that died 202 @type process_name: str 203 @param exit_code: exit code of remote process 204 @type exit_code: int 205 @return: code, msg, ignore 206 @rtype: int, str, int 207 """ 208 for l in self.listeners: 209 try: 210 l.process_died(process_name, exit_code) 211 except: 212 self.logger.error(traceback.format_exc()) 213 return 1, '', 0
214
215 - def log(self, client, level, message):
216 """ 217 Report a log message to the server 218 @param client: name of client 219 @type client: str 220 @param level: log level (uses rosgraph_msgs.msg.Log levels) 221 @type level: int 222 @param message: message to log 223 @type message: str 224 """ 225 try: 226 if level >= Log.ERROR: 227 printerrlog("[%s]: %s"%(client, message)) 228 else: 229 #hack due to the fact that we only have one INFO level 230 if 'started with pid' in message: 231 printlog_bold("[%s]: %s"%(client, message)) 232 else: 233 printlog("[%s]: %s"%(client, message)) 234 except: 235 # can't trust the logging system at this point, so just dump to screen 236 traceback.print_exc() 237 return 1, '', 1
238
239 -class ROSLaunchChildHandler(ROSLaunchBaseHandler):
240 """ 241 XML-RPC API implementation for child roslaunches 242 NOTE: the client handler runs a process monitor so that 243 it can track processes across requests 244 """ 245
246 - def __init__(self, run_id, name, server_uri, pm):
247 """ 248 @param server_uri: XML-RPC URI of server 249 @type server_uri: str 250 @param pm: process monitor to use 251 @type pm: L{ProcessMonitor} 252 @raise RLException: If parameters are invalid 253 """ 254 super(ROSLaunchChildHandler, self).__init__(pm) 255 if server_uri is None: 256 raise RLException("server_uri is not initialized") 257 self.run_id = run_id 258 259 # parse the URI to make sure it's valid 260 _, urlport = network.parse_http_host_and_port(server_uri) 261 if urlport <= 0: 262 raise RLException("ERROR: roslaunch server URI is not a valid XML-RPC URI. Value is [%s]"%m.uri) 263 264 self.name = name 265 self.pm = pm 266 self.server_uri = server_uri 267 self.server = ServerProxy(server_uri)
268
269 - def _shutdown(self, reason):
270 """ 271 xmlrpc.XmlRpcHandler API: inform handler of shutdown 272 @param reason: human-readable shutdown reason 273 @type reason: str 274 """ 275 if self.pm is not None: 276 self.pm.shutdown() 277 self.pm.join() 278 self.pm = None
279
280 - def shutdown(self):
281 """ 282 @return: code, msg, ignore 283 @rtype: int, str, int 284 """ 285 self._shutdown("external call") 286 return 1, "success", 1
287
288 - def _log(self, level, message):
289 """ 290 log message to log file and roslaunch server 291 @param level: log level 292 @type level: int 293 @param message: message to log 294 @type message: str 295 """ 296 try: 297 if self.logger is not None: 298 self.logger.debug(message) 299 if self.server is not None: 300 self.server.log(str(self.name), level, str(message)) 301 except: 302 self.logger.error(traceback.format_exc())
303
304 - def launch(self, launch_xml):
305 """ 306 Launch the roslaunch XML file. Because this is a child 307 roslaunch, it will not set parameters nor manipulate the 308 master. Call blocks until launch is complete 309 @param xml: roslaunch XML file to launch 310 @type xml: str 311 @return: code, msg, [ [ successful launches], [failed launches] ] 312 @rtype: int, str, [ [str], [str] ] 313 """ 314 if self.pm is None: 315 return 0, "uninitialized", -1 316 317 rosconfig = roslaunch.config.ROSLaunchConfig() 318 try: 319 roslaunch.xmlloader.XmlLoader().load_string(launch_xml, rosconfig) 320 except roslaunch.xmlloader.XmlParseException as e: 321 return -1, "ERROR: %s"%e, [[], []] 322 323 # won't actually do anything other than local, but still required 324 rosconfig.assign_machines() 325 326 try: 327 # roslaunch clients try to behave like normal roslaunches as much as possible. It's 328 # mainly the responsibility of the roslaunch server to not give us any XML that might 329 # cause conflict (e.g. master tags, param tags, etc...). 330 self._log(Log.INFO, "launching nodes...") 331 runner = ROSLaunchRunner(self.run_id, rosconfig, server_uri=self.server_uri, pmon=self.pm) 332 succeeded, failed = runner.launch() 333 self._log(Log.INFO, "... done launching nodes") 334 # enable the process monitor to exit of all processes die 335 self.pm.registrations_complete() 336 return 1, "launched", [ succeeded, failed ] 337 except Exception as e: 338 return 0, "ERROR: %s"%traceback.format_exc(), [[], []]
339 340 _STARTUP_TIMEOUT = 5.0 #seconds 341
342 -class ROSLaunchNode(xmlrpc.XmlRpcNode):
343 """ 344 Base XML-RPC server for roslaunch parent/child processes 345 """ 346
347 - def __init__(self, handler):
348 """ 349 @param handler: xmlrpc api handler 350 @type handler: L{ROSLaunchBaseHandler} 351 """ 352 super(ROSLaunchNode, self).__init__(0, handler)
353
354 - def start(self):
355 """ 356 Startup roslaunch server XML-RPC services 357 @raise RLException: if server fails to start 358 """ 359 logger = logging.getLogger('roslaunch.server') 360 logger.info("starting roslaunch XML-RPC server") 361 super(ROSLaunchNode, self).start() 362 363 # wait for node thread to initialize 364 timeout_t = time.time() + _STARTUP_TIMEOUT 365 logger.info("waiting for roslaunch XML-RPC server to initialize") 366 while not self.uri and time.time() < timeout_t: 367 time.sleep(0.01) 368 if not self.uri: 369 raise RLException("XML-RPC initialization failed") 370 371 # Make sure our xmlrpc server is actually up. We've seen very 372 # odd cases where remote nodes are unable to contact the 373 # server but have been unable to prove this is the cause. 374 server_up = False 375 while not server_up and time.time() < timeout_t: 376 try: 377 code, msg, val = ServerProxy(self.uri).get_pid() 378 if val != os.getpid(): 379 raise RLException("Server at [%s] did not respond with correct PID. There appears to be something wrong with the networking configuration"%self.uri) 380 server_up = True 381 except IOError: 382 # presumably this can occur if we call in a small time 383 # interval between the server socket port being 384 # assigned and the XMLRPC server initializing, but it 385 # is highly unlikely and unconfirmed 386 time.sleep(0.1) 387 except socket.error as e: 388 if e.errno == errno.EHOSTUNREACH: 389 p = urlparse(self.uri) 390 raise RLException("Unable to contact the address [%s], which should be local.\nThis is generally caused by:\n * bad local network configuration\n * bad ROS_IP environment variable\n * bad ROS_HOSTNAME environment variable\nCan you ping %s?"%(self.uri, p.hostname)) 391 else: 392 time.sleep(0.1) 393 if not server_up: 394 p = urlparse(self.uri) 395 raise RLException("""Unable to contact my own server at [%s]. 396 This usually means that the network is not configured properly. 397 398 A common cause is that the machine cannot ping itself. Please check 399 for errors by running: 400 401 \tping %s 402 403 For more tips, please see 404 405 \thttp://www.ros.org/wiki/ROS/NetworkSetup 406 """%(self.uri, p.hostname)) 407 printlog_bold("started roslaunch server %s"%(self.uri))
408
409 - def run(self):
410 """ 411 run() should not be called by higher-level code. ROSLaunchNode 412 overrides underlying xmlrpc.XmlRpcNode implementation in order 413 to log errors. 414 """ 415 try: 416 super(ROSLaunchNode, self).run() 417 except: 418 logging.getLogger("roslaunch.remote").error(traceback.format_exc()) 419 print("ERROR: failed to launch XML-RPC server for roslaunch", file=sys.stderr)
420
421 -class ROSLaunchParentNode(ROSLaunchNode):
422 """ 423 XML-RPC server for parent roslaunch. 424 """ 425
426 - def __init__(self, rosconfig, pm):
427 """ 428 @param config: ROSConfig launch configuration 429 @type config: L{ROSConfig} 430 @param pm: process monitor 431 @type pm: L{ProcessMonitor} 432 """ 433 self.rosconfig = rosconfig 434 self.listeners = [] 435 self.child_processes = {} #{ child-name : ChildROSLaunchProcess}. 436 437 if pm is None: 438 raise RLException("cannot create parent node: pm is not initialized") 439 handler = ROSLaunchParentHandler(pm, self.child_processes, self.listeners) 440 super(ROSLaunchParentNode, self).__init__(handler)
441
442 - def add_child(self, name, p):
443 """ 444 @param name: child roslaunch's name. NOTE: \a name is not 445 the same as the machine config key. 446 @type name: str 447 @param p: process handle of child 448 @type p: L{Process} 449 """ 450 self.child_processes[name] = p
451
452 - def add_process_listener(self, l):
453 """ 454 Listen to events about remote processes dying. Not 455 threadsafe. Must be called before processes started. 456 @param l: Process listener 457 @type l: L{ProcessListener} 458 """ 459 self.listeners.append(l)
460
461 -class _ProcessListenerForwarder(ProcessListener):
462 """ 463 Simple listener that forwards ProcessListener events to a roslaunch server 464 """
465 - def __init__(self, server):
466 self.server = server
467 - def process_died(self, process_name, exit_code):
468 try: 469 self.server.process_died(process_name, exit_code) 470 except Exception as e: 471 logging.getLogger("roslaunch.remote").error(traceback.format_exc())
472
473 -class ROSLaunchChildNode(ROSLaunchNode):
474 """ 475 XML-RPC server for roslaunch child processes 476 """ 477
478 - def __init__(self, run_id, name, server_uri, pm):
479 """ 480 ## Startup roslaunch remote client XML-RPC services. Blocks until shutdown 481 ## @param name: name of remote client 482 ## @type name: str 483 ## @param server_uri: XML-RPC URI of roslaunch server 484 ## @type server_uri: str 485 ## @return: XML-RPC URI 486 ## @rtype: str 487 """ 488 self.logger = logging.getLogger("roslaunch.server") 489 self.run_id = run_id 490 self.name = name 491 self.server_uri = server_uri 492 self.pm = pm 493 494 if self.pm is None: 495 raise RLException("cannot create child node: pm is not initialized") 496 handler = ROSLaunchChildHandler(self.run_id, self.name, self.server_uri, self.pm) 497 super(ROSLaunchChildNode, self).__init__(handler)
498
499 - def _register_with_server(self):
500 """ 501 Register child node with server 502 """ 503 name = self.name 504 self.logger.info("attempting to register with roslaunch parent [%s]"%self.server_uri) 505 try: 506 server = ServerProxy(self.server_uri) 507 code, msg, _ = server.register(name, self.uri) 508 if code != 1: 509 raise RLException("unable to register with roslaunch server: %s"%msg) 510 except Exception as e: 511 self.logger.error("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc())) 512 # fail 513 raise RLException("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc())) 514 515 self.logger.debug("child registered with server") 516 517 # register printlog handler so messages are funneled to remote 518 def serverlog(msg): 519 server.log(name, Log.INFO, msg)
520 def servererrlog(msg): 521 server.log(name, Log.ERROR, msg)
522 add_printlog_handler(serverlog) 523 add_printerrlog_handler(servererrlog) 524 525 # register process listener to forward process death events to main server 526 self.pm.add_process_listener(_ProcessListenerForwarder(server)) 527
528 - def start(self):
529 """ 530 Initialize child. Must be called before run 531 """ 532 self.logger.info("starting roslaunch child process [%s], server URI is [%s]", self.name, self.server_uri) 533 super(ROSLaunchChildNode, self).start() 534 self._register_with_server()
535