1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
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 from roslaunch.nodeprocess import DEFAULT_TIMEOUT_SIGINT, DEFAULT_TIMEOUT_SIGTERM
74
75 from roslaunch.launch import ROSLaunchRunner
76 from roslaunch.core import RLException, \
77 add_printlog_handler, add_printerrlog_handler, printlog, printerrlog, printlog_bold
78
79
80 from rosgraph_msgs.msg import Log
81
82
84 """
85 API for remote roslaunch processes
86 """
90
93
95 """
96 Common XML-RPC API for the roslaunch server and child node
97 """
99 self.pm = pm
100 self.logger = logging.getLogger('roslaunch.server')
101 if self.pm is None:
102 raise RLException("cannot create xmlrpc handler: pm is not initialized")
103
104
105
107 """
108 @return: code, msg, process list.
109 Process list is two lists, where first list of
110 active process names along with the number of times that
111 process has been spawned. Second list contains dead process
112 names and their spawn count.
113 @rtype: int, str, [[(str, int),], [(str,int),]]
114 """
115 return 1, "processes on parent machine", self.pm.get_process_names_with_spawn_count()
116
118 """
119 @return: dictionary of metadata about process. Keys vary by implementation
120 @rtype: int, str, dict
121 """
122 p = self.pm.get_process(process_name)
123 if p is None:
124 return -1, "no process by that name", {}
125 else:
126 return 1, "process info", p.get_info()
127
129 """
130 @return: code, msg, pid
131 @rtype: int, str, int
132 """
133
134 pid = os.getpid()
135 return 1, str(pid), pid
136
138 """
139 @return: code, msg, list of node names
140 @rtype: int, str, [str]
141 """
142 if self.pm is None:
143 return 0, "uninitialized", []
144 return 1, "node names", self.pm.get_active_names()
145
147 """
148 xmlrpc.XmlRpcHandler API: inform handler of shutdown
149 @param reason: human-readable shutdown reason
150 @type reason: str
151 """
152 return 1, '', 1
153
154
155
157 """
158 XML-RPC API for the roslaunch server node
159 """
160
161 - def __init__(self, pm, child_processes, listeners):
162 """
163 @param child_processes: Map of remote processes so that server can update processes
164 with information as children register. Handler will not modify
165 keys.
166 @type child_processes: {name : ChildROSLaunchProcess}.
167 @param listeners [ProcessListener]: list of
168 listeners to notify when process_died events occur.
169 """
170 super(ROSLaunchParentHandler, self).__init__(pm)
171 self.child_processes = child_processes
172 self.listeners = listeners
173
175 """
176 Registration callback from newly launched roslaunch clients
177 @param client: name of client
178 @type client: str
179 @param uri: XML-RPC URI of client
180 @type uri: str
181 @return: code, msg, ignore
182 @rtype: int, str, int
183 """
184 if client not in self.child_processes:
185 self.logger.error("Unknown child [%s] registered with server", client)
186 return -1, "unknown child [%s]"%client, 0
187 else:
188 self.logger.info("child [%s] registered with server, uri[%s]", client, uri)
189 self.child_processes[client].set_uri(uri)
190 return 1, "registered", 1
191
193 """
194 List the roslaunch child processes.
195 @return int, str, [str]: code, msg, list of the roslaunch children URIS
196 """
197 return 1, 'roslaunch children', [v.uri for v in self.child_processes.values() if v.uri is not None]
198
200 """
201 Inform roslaunch server that a remote process has died
202 @param process_name: name of process that died
203 @type process_name: str
204 @param exit_code: exit code of remote process
205 @type exit_code: int
206 @return: code, msg, ignore
207 @rtype: int, str, int
208 """
209 for l in self.listeners:
210 try:
211 l.process_died(process_name, exit_code)
212 except:
213 self.logger.error(traceback.format_exc())
214 return 1, '', 0
215
216 - def log(self, client, level, message):
217 """
218 Report a log message to the server
219 @param client: name of client
220 @type client: str
221 @param level: log level (uses rosgraph_msgs.msg.Log levels)
222 @type level: int
223 @param message: message to log
224 @type message: str
225 """
226 try:
227 if level >= Log.ERROR:
228 printerrlog("[%s]: %s"%(client, message))
229 else:
230
231 if 'started with pid' in message:
232 printlog_bold("[%s]: %s"%(client, message))
233 else:
234 printlog("[%s]: %s"%(client, message))
235 except:
236
237 traceback.print_exc()
238 return 1, '', 1
239
241 """
242 XML-RPC API implementation for child roslaunches
243 NOTE: the client handler runs a process monitor so that
244 it can track processes across requests
245 """
246
248 """
249 @param server_uri: XML-RPC URI of server
250 @type server_uri: str
251 @param pm: process monitor to use
252 @type pm: L{ProcessMonitor}
253 @param sigint_timeout: The SIGINT timeout used when killing nodes (in seconds).
254 @type sigint_timeout: float
255 @param sigterm_timeout: The SIGTERM timeout used when killing nodes if SIGINT does not stop the node (
256 in seconds).
257 @type sigterm_timeout: float
258 @raise RLException: If parameters are invalid
259 """
260 super(ROSLaunchChildHandler, self).__init__(pm)
261 if server_uri is None:
262 raise RLException("server_uri is not initialized")
263 self.run_id = run_id
264
265
266 _, urlport = network.parse_http_host_and_port(server_uri)
267 if urlport <= 0:
268 raise RLException("ERROR: roslaunch server URI is not a valid XML-RPC URI. Value is [%s]"%m.uri)
269
270 self.name = name
271 self.pm = pm
272 self.server_uri = server_uri
273 self.sigint_timeout = sigint_timeout
274 self.sigterm_timeout = sigterm_timeout
275 self.server = ServerProxy(server_uri)
276
278 """
279 xmlrpc.XmlRpcHandler API: inform handler of shutdown
280 @param reason: human-readable shutdown reason
281 @type reason: str
282 """
283 if self.pm is not None:
284 self.pm.shutdown()
285 self.pm.join()
286 self.pm = None
287
289 """
290 @return: code, msg, ignore
291 @rtype: int, str, int
292 """
293 self._shutdown("external call")
294 return 1, "success", 1
295
296 - def _log(self, level, message):
297 """
298 log message to log file and roslaunch server
299 @param level: log level
300 @type level: int
301 @param message: message to log
302 @type message: str
303 """
304 try:
305 if self.logger is not None:
306 self.logger.debug(message)
307 if self.server is not None:
308 self.server.log(str(self.name), level, str(message))
309 except:
310 self.logger.error(traceback.format_exc())
311
312 - def launch(self, launch_xml):
313 """
314 Launch the roslaunch XML file. Because this is a child
315 roslaunch, it will not set parameters nor manipulate the
316 master. Call blocks until launch is complete
317 @param xml: roslaunch XML file to launch
318 @type xml: str
319 @return: code, msg, [ [ successful launches], [failed launches] ]
320 @rtype: int, str, [ [str], [str] ]
321 """
322 if self.pm is None:
323 return 0, "uninitialized", -1
324
325 rosconfig = roslaunch.config.ROSLaunchConfig()
326 try:
327 roslaunch.xmlloader.XmlLoader().load_string(launch_xml, rosconfig)
328 except roslaunch.xmlloader.XmlParseException as e:
329 return -1, "ERROR: %s"%e, [[], []]
330
331
332 rosconfig.assign_machines()
333
334 try:
335
336
337
338 self._log(Log.INFO, "launching nodes...")
339 runner = ROSLaunchRunner(self.run_id, rosconfig, server_uri=self.server_uri, pmon=self.pm,
340 sigint_timeout=self.sigint_timeout, sigterm_timeout=self.sigterm_timeout)
341 succeeded, failed = runner.launch()
342 self._log(Log.INFO, "... done launching nodes")
343
344 self.pm.registrations_complete()
345 return 1, "launched", [ succeeded, failed ]
346 except Exception as e:
347 return 0, "ERROR: %s"%traceback.format_exc(), [[], []]
348
349 _STARTUP_TIMEOUT = 5.0
350
352 """
353 Base XML-RPC server for roslaunch parent/child processes
354 """
355
357 """
358 @param handler: xmlrpc api handler
359 @type handler: L{ROSLaunchBaseHandler}
360 """
361 super(ROSLaunchNode, self).__init__(0, handler)
362
364 """
365 Startup roslaunch server XML-RPC services
366 @raise RLException: if server fails to start
367 """
368 logger = logging.getLogger('roslaunch.server')
369 logger.info("starting roslaunch XML-RPC server")
370 super(ROSLaunchNode, self).start()
371
372
373 timeout_t = time.time() + _STARTUP_TIMEOUT
374 logger.info("waiting for roslaunch XML-RPC server to initialize")
375 while not self.uri and time.time() < timeout_t:
376 time.sleep(0.01)
377 if not self.uri:
378 raise RLException("XML-RPC initialization failed")
379
380
381
382
383 server_up = False
384 while not server_up and time.time() < timeout_t:
385 try:
386 code, msg, val = ServerProxy(self.uri).get_pid()
387 if val != os.getpid():
388 raise RLException("Server at [%s] did not respond with correct PID. There appears to be something wrong with the networking configuration"%self.uri)
389 server_up = True
390 except IOError:
391
392
393
394
395 time.sleep(0.1)
396 except socket.error as e:
397 if e.errno == errno.EHOSTUNREACH:
398 p = urlparse(self.uri)
399 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))
400 else:
401 time.sleep(0.1)
402 if not server_up:
403 p = urlparse(self.uri)
404 raise RLException("""Unable to contact my own server at [%s].
405 This usually means that the network is not configured properly.
406
407 A common cause is that the machine cannot connect to itself. Please check
408 for errors by running:
409
410 \tping %s
411
412 For more tips, please see
413
414 \thttp://wiki.ros.org/ROS/NetworkSetup
415 """%(self.uri, p.hostname))
416 printlog_bold("started roslaunch server %s"%(self.uri))
417
419 """
420 run() should not be called by higher-level code. ROSLaunchNode
421 overrides underlying xmlrpc.XmlRpcNode implementation in order
422 to log errors.
423 """
424 try:
425 super(ROSLaunchNode, self).run()
426 except:
427 logging.getLogger("roslaunch.remote").error(traceback.format_exc())
428 print("ERROR: failed to launch XML-RPC server for roslaunch", file=sys.stderr)
429
431 """
432 XML-RPC server for parent roslaunch.
433 """
434
436 """
437 @param config: ROSConfig launch configuration
438 @type config: L{ROSConfig}
439 @param pm: process monitor
440 @type pm: L{ProcessMonitor}
441 """
442 self.rosconfig = rosconfig
443 self.listeners = []
444 self.child_processes = {}
445
446 if pm is None:
447 raise RLException("cannot create parent node: pm is not initialized")
448 handler = ROSLaunchParentHandler(pm, self.child_processes, self.listeners)
449 super(ROSLaunchParentNode, self).__init__(handler)
450
452 """
453 @param name: child roslaunch's name. NOTE: \a name is not
454 the same as the machine config key.
455 @type name: str
456 @param p: process handle of child
457 @type p: L{Process}
458 """
459 self.child_processes[name] = p
460
462 """
463 Listen to events about remote processes dying. Not
464 threadsafe. Must be called before processes started.
465 @param l: Process listener
466 @type l: L{ProcessListener}
467 """
468 self.listeners.append(l)
469
471 """
472 Simple listener that forwards ProcessListener events to a roslaunch server
473 """
477 try:
478 self.server.process_died(process_name, exit_code)
479 except Exception as e:
480 logging.getLogger("roslaunch.remote").error(traceback.format_exc())
481
483 """
484 XML-RPC server for roslaunch child processes
485 """
486
488 """
489 ## Startup roslaunch remote client XML-RPC services. Blocks until shutdown
490 ## @param name: name of remote client
491 ## @type name: str
492 ## @param server_uri: XML-RPC URI of roslaunch server
493 ## @type server_uri: str
494 ## @param sigint_timeout: The SIGINT timeout used when killing nodes (in seconds).
495 ## @type sigint_timeout: float
496 ## @param sigterm_timeout: The SIGTERM timeout used when killing nodes if SIGINT does not stop the node (
497 ## in seconds).
498 ## @type sigterm_timeout: float
499 ## @return: XML-RPC URI
500 ## @rtype: str
501 """
502 self.logger = logging.getLogger("roslaunch.server")
503 self.run_id = run_id
504 self.name = name
505 self.server_uri = server_uri
506 self.pm = pm
507
508 if self.pm is None:
509 raise RLException("cannot create child node: pm is not initialized")
510 handler = ROSLaunchChildHandler(self.run_id, self.name, self.server_uri, self.pm,
511 sigint_timeout=sigint_timeout, sigterm_timeout=sigterm_timeout)
512 super(ROSLaunchChildNode, self).__init__(handler)
513
515 """
516 Register child node with server
517 """
518 name = self.name
519 self.logger.info("attempting to register with roslaunch parent [%s]"%self.server_uri)
520 try:
521 server = ServerProxy(self.server_uri)
522 code, msg, _ = server.register(name, self.uri)
523 if code != 1:
524 raise RLException("unable to register with roslaunch server: %s"%msg)
525 except Exception as e:
526 self.logger.error("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc()))
527
528 raise RLException("Exception while registering with roslaunch parent [%s]: %s"%(self.server_uri, traceback.format_exc()))
529
530 self.logger.debug("child registered with server")
531
532
533 def serverlog(msg):
534 server.log(name, Log.INFO, msg)
535 def servererrlog(msg):
536 server.log(name, Log.ERROR, msg)
537 add_printlog_handler(serverlog)
538 add_printerrlog_handler(servererrlog)
539
540
541 self.pm.add_process_listener(_ProcessListenerForwarder(server))
542
544 """
545 Initialize child. Must be called before run
546 """
547 self.logger.info("starting roslaunch child process [%s], server URI is [%s]", self.name, self.server_uri)
548 super(ROSLaunchChildNode, self).start()
549 self._register_with_server()
550