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 """
36 Top-level implementation of launching processes. Coordinates
37 lower-level libraries.
38 """
39
40 import os
41 import logging
42 import sys
43 import time
44
45 import roslib.names
46 import roslib.network
47
48 from roslaunch.core import *
49 from roslaunch.config import ROSLaunchConfig
50 from roslaunch.nodeprocess import create_master_process, create_node_process
51 from roslaunch.pmon import start_process_monitor, ProcessListener, FatalProcessLaunch
52
53 from roslaunch.rlutil import update_terminal_name
54
55 _TIMEOUT_MASTER_START = 10.0
56 _TIMEOUT_MASTER_STOP = 10.0
57
58 _ID = '/roslaunch'
59
61
63 """
64 Validate the configuration of a master we are about to launch. Ths
65 validation already assumes that no existing master is running at
66 this configuration and merely checks configuration for a new
67 launch.
68 """
69
70
71
72
73
74
75
76 if not roslib.network.is_local_address(m.get_host()):
77
78
79 if is_core:
80
81
82
83 try:
84 reverse_ip = socket.gethostbyname(m.get_host())
85 local_addrs = roslib.network.get_local_addresses()
86 printerrlog("""WARNING: IP address %s for local hostname '%s' does not appear to match
87 any local IP address (%s). Your ROS nodes may fail to communicate.
88
89 Please use ROS_IP to set the correct IP address to use."""%(reverse_ip, m.get_host(), ','.join(local_addrs)))
90 except:
91 printerrlog("""WARNING: local hostname '%s' does not map to an IP address.
92 Your ROS nodes may fail to communicate.
93
94 Please use ROS_IP to set the correct IP address to use."""%(m.get_host()))
95
96 else:
97
98 raise RLException("ERROR: unable to contact ROS master at [%s]"%(m.uri))
99
100 if is_core:
101
102
103 env_uri = roslib.rosenv.get_master_uri()
104 env_host, env_port = roslib.network.parse_http_host_and_port(env_uri)
105
106 if not roslib.network.is_local_address(env_host):
107
108 printerrlog("WARNING: ROS_MASTER_URI [%s] host is not set to this machine"%(env_uri))
109 elif env_port != m.get_port():
110
111 printerrlog("WARNING: ROS_MASTER_URI port [%s] does not match this roscore [%s]"%(env_port, m.get_port()))
112
114 splits = [s for s in p.split(roslib.names.SEP) if s]
115 curr =roslib.names.SEP
116 parents = [curr]
117 for s in splits[:-1]:
118 next_ = curr + s + roslib.names.SEP
119 parents.append(next_)
120 curr = next_
121 return parents
122
124 """
125 Reduce clear_params such that only the highest-level namespaces
126 are represented for overlapping namespaces. e.g. if both /foo/ and
127 /foo/bar are present, return just /foo/.
128
129 @param params: paremter namees
130 @type params: [str]
131 @return: unified parameters
132 @rtype: [str]
133 """
134
135
136
137 canon_params = []
138 for p in params:
139 if not p[-1] == roslib.names.SEP:
140 p += roslib.names.SEP
141 if not p in canon_params:
142 canon_params.append(p)
143
144 clear_params = canon_params[:]
145 for p in canon_params:
146 for parent in _all_namespace_parents(p):
147 if parent in canon_params and p in clear_params and p != '/':
148 clear_params.remove(p)
149 return clear_params
150
152 """
153 Utility function to strip illegal characters from hostname. This
154 is implemented to be correct, not efficient."""
155
156
157 fixed = 'host_'
158
159 hostname = hostname.lower()
160 for c in hostname:
161
162 if (c >= 'a' and c <= 'z') or \
163 (c >= '0' and c <= '9'):
164 fixed+=c
165 else:
166 fixed+='_'
167 return fixed
168
170 """
171 Helper class to manage distributing process events. It functions as
172 a higher level aggregator of events. In particular, events about
173 remote and local processes require different mechanisms for being
174 caught and reported.
175 """
177 self.process_listeners = []
178
180 """
181 Add listener to list of listeners. Not threadsafe.
182 @param l: listener
183 @type l: L{ProcessListener}
184 """
185 self.process_listeners.append(l)
186
188 """
189 ProcessListener callback
190 """
191 for l in self.process_listeners:
192 try:
193 l.process_died(process_name, exit_code)
194 except Exception, e:
195 import traceback
196 logging.getLogger('roslaunch').error(traceback.format_exc())
197
199 """
200 Listener interface for events related to ROSLaunch.
201 ROSLaunchListener is currently identical to the lower-level
202 L{roslaunch.pmon.ProcessListener} interface, but is separate for
203 architectural reasons. The lower-level
204 L{roslaunch.pmon.ProcessMonitor} does not provide events about
205 remotely running processes.
206 """
207
209 """
210 Notifies listener that process has died. This callback only
211 occurs for processes that die during normal process monitor
212 execution -- processes that are forcibly killed during
213 L{roslaunch.pmon.ProcessMonitor} shutdown are not reported.
214 @param process_name: name of process
215 @type process_name: str
216 @param exit_code int: exit code of process. If None, it means
217 that L{roslaunch.pmon.ProcessMonitor} was unable to determine an exit code.
218 @type exit_code: int
219 """
220 pass
221
222
224 """
225 Runs a roslaunch. The normal sequence of API calls is L{launch()}
226 followed by L{spin()}. An external thread can call L{stop()}; otherwise
227 the runner will block until an exit signal. Another usage is to
228 call L{launch()} followed by repeated calls to L{spin_once()}. This usage
229 allows the main thread to continue to do work while processes are
230 monitored.
231 """
232
233 - def __init__(self, run_id, server_uri=None, pmon=None, is_core=False, remote_runner=None):
234 """
235 @param run_id: /run_id for this launch. If the core is not
236 running, this value will be used to initialize /run_id. If
237 the core is already running, this value will be checked
238 against the value stored on the core. L{ROSLaunchRunner} will
239 fail during L{launch()} if they do not match.
240 @type run_id: str
241 @param server_uri: XML-RPC URI of roslaunch server.
242 @type server_uri: str
243 @param pmon: optionally override the process
244 monitor the runner uses for starting and tracking processes
245 @type pmon: L{ProcessMonitor}
246
247 @param is_core: if True, this runner is a roscore
248 instance. This affects the error behavior if a master is
249 already running -- aborts if is_core is True and a core is
250 detected.
251 @type is_core: bool
252 @param remote_runner: remote roslaunch process runner
253 """
254 if run_id is None:
255 raise RLException("run_id is None")
256 self.run_id = run_id
257 self.server_uri = server_uri
258
259 self.is_core = is_core
260 self.logger = logging.getLogger('roslaunch')
261 self.pm = pmon or start_process_monitor()
262
263
264
265
266 self.listeners = _ROSLaunchListeners()
267 if self.pm is None:
268 raise RLException("unable to initialize roslaunch process monitor")
269 if self.pm.is_shutdown:
270 raise RLException("bad roslaunch process monitor initialization: process monitor is already dead")
271
272 self.pm.add_process_listener(self.listeners)
273
274 self.remote_runner = remote_runner
275
277 """
278 Add listener to list of listeners. Not threadsafe. Must be
279 called before processes started.
280 @param l: listener
281 @type l: L{ProcessListener}
282 """
283 self.listeners.add_process_listener(l)
284
286 """
287 Load parameters onto the parameter server
288 """
289 self.logger.info("load_parameters starting ...")
290 param_server = config.master.get()
291 p = None
292 try:
293
294 param_server_multi = config.master.get_multi()
295
296
297
298 for p in _unify_clear_params(config.clear_params):
299 if param_server.hasParam(_ID, p)[2]:
300
301 param_server_multi.deleteParam(_ID, p)
302 r = param_server_multi()
303 for code, msg, _ in r:
304 if code != 1:
305 raise RLException("Failed to clear parameter: %s"%(msg))
306
307
308 param_server_multi = config.master.get_multi()
309 for p in config.params.itervalues():
310
311
312 param_server_multi.setParam(_ID, p.key, p.value)
313 r = param_server_multi()
314 for code, msg, _ in r:
315 if code != 1:
316 raise RLException("Failed to set parameter: %s"%(msg))
317 except RLException:
318 raise
319 except Exception, e:
320 printerrlog("load_parameters: unable to set parameters (last param was [%s]): %s"%(p,e))
321 raise
322 self.logger.info("... load_parameters complete")
323
324
326 """
327 Launch all the declared nodes/master
328 @return: two lists of node names where the first
329 is the nodes that successfully launched and the second is the
330 nodes that failed to launch.
331 @rtype: [[str], [str]]
332 """
333 succeeded = []
334 failed = []
335 self.logger.info("launch_nodes: launching local nodes ...")
336 local_nodes = config.nodes
337
338
339 local_nodes = [n for n in config.nodes if is_machine_local(n.machine)]
340
341 for node in local_nodes:
342 proc, success = self.launch_node(config, node)
343 if success:
344 succeeded.append(str(proc))
345 else:
346 failed.append(str(proc))
347
348 if self.remote_runner:
349 self.logger.info("launch_nodes: launching remote nodes ...")
350 r_succ, r_fail = self.remote_runner.launch_remote_nodes()
351 succeeded.extend(r_succ)
352 failed.extend(r_fail)
353
354 self.logger.info("... launch_nodes complete")
355 return succeeded, failed
356
358 """
359 Validates master configuration and changes the master URI if
360 necessary. Also shuts down any existing master.
361 @raise RLException: if existing master cannot be killed
362 """
363 m = config.master
364 self.logger.info("initial ROS_MASTER_URI is %s", m.uri)
365 if m.auto in [m.AUTO_START, m.AUTO_RESTART]:
366 running = m.is_running()
367 if m.auto == m.AUTO_RESTART and running:
368 print "shutting down existing master"
369 try:
370 m.get().shutdown(_ID, 'roslaunch restart request')
371 except:
372 pass
373 timeout_t = time.time() + _TIMEOUT_MASTER_STOP
374 while m.is_running() and time.time() < timeout_t:
375 time.sleep(0.1)
376 if m.is_running():
377 raise RLException("ERROR: could not stop existing master")
378 running = False
379 if not running:
380
381 olduri = m.uri
382 m.uri = remap_localhost_uri(m.uri, True)
383
384
385
386
387 hostname, _ = roslib.network.parse_http_host_and_port(m.uri)
388 local_addrs = roslib.network.get_local_addresses()
389 import socket
390 reverse_ip = socket.gethostbyname(hostname)
391
392 if reverse_ip not in local_addrs and not reverse_ip.startswith('127.'):
393 self.logger.warn("IP address %s local hostname '%s' not in local addresses (%s)."%(reverse_ip, hostname, ','.join(local_addrs)))
394 print >> sys.stderr, \
395 """WARNING: IP address %s for local hostname '%s' does not appear to match
396 any local IP address (%s). Your ROS nodes may fail to communicate.
397
398 Please use ROS_IP to set the correct IP address to use."""%(reverse_ip, hostname, ','.join(local_addrs))
399
400 if m.uri != olduri:
401 self.logger.info("changing ROS_MASTER_URI to [%s] for starting master locally", m.uri)
402 print "changing ROS_MASTER_URI to [%s] for starting master locally"%m.uri
403
405 """
406 Launches master if requested. Must be run after L{_setup_master()}.
407 @raise RLException: if master launch fails
408 """
409 m = config.master
410 is_running = m.is_running()
411
412 if self.is_core and is_running:
413 raise RLException("roscore cannot run as another roscore/master is already running. \nPlease kill other roscore/master processes before relaunching.\nThe ROS_MASTER_URI is %s"%(m.uri))
414
415 if not is_running:
416 validate_master_launch(m, self.is_core)
417
418 printlog("auto-starting new master")
419 p = create_master_process(self.run_id, m.type, get_ros_root(), m.get_port())
420 self.pm.register_core_proc(p)
421 success = p.start()
422 if not success:
423 raise RLException("ERROR: unable to auto-start master process")
424 timeout_t = time.time() + _TIMEOUT_MASTER_START
425 while not m.is_running() and time.time() < timeout_t:
426 time.sleep(0.1)
427
428 if not m.is_running():
429 raise RLException("ERROR: could not contact master [%s]"%m.uri)
430
431 printlog_bold("ROS_MASTER_URI=%s"%m.uri)
432
433
434
435 update_terminal_name(m.uri)
436
437
438 param_server = m.get()
439
440
441 self._check_and_set_run_id(param_server, self.run_id)
442
443 if self.server_uri:
444
445
446 hostname, port = roslib.network.parse_http_host_and_port(self.server_uri)
447 hostname = _hostname_to_rosname(hostname)
448 self.logger.info("setting /roslaunch/uris/%s__%s' to %s"%(hostname, port, self.server_uri))
449 param_server.setParam(_ID, '/roslaunch/uris/%s__%s'%(hostname, port),self.server_uri)
450
452 """
453 Initialize self.run_id to existing value or setup parameter
454 server with /run_id set to default_run_id
455 @param default_run_id: run_id to use if value is not set
456 @type default_run_id: str
457 @param param_server: parameter server proxy
458 @type param_server: xmlrpclib.ServerProxy
459 """
460 code, _, val = param_server.hasParam(_ID, '/run_id')
461 if code == 1 and not val:
462 printlog_bold("setting /run_id to %s"%run_id)
463 param_server.setParam('/roslaunch', '/run_id', run_id)
464 else:
465
466 code, _, val = param_server.getParam('/roslaunch', '/run_id')
467 if code != 1:
468
469
470 raise RLException("ERROR: unable to retrieve /run_id from parameter server")
471 if run_id != val:
472 raise RLException("run_id on parameter server does not match declared run_id: %s vs %s"%(val, run_id))
473
474
475
477 """
478 Launch a single L{Executable} object. Blocks until executable finishes.
479 @param e: Executable
480 @type e: L{Executable}
481 @raise RLException: if exectuable fails. Failure includes non-zero exit code.
482 """
483 try:
484
485 cmd = e.command
486 if isinstance(e, RosbinExecutable):
487 cmd = os.path.join(get_ros_root(), 'bin', cmd)
488 cmd = "%s %s"%(cmd, ' '.join(e.args))
489 print "running %s"%cmd
490 local_machine = config.machines['']
491 import roslaunch.node_args
492 env = roslaunch.node_args.create_local_process_env(None, local_machine, config.master.uri)
493 import subprocess
494 retcode = subprocess.call(cmd, shell=True, env=env)
495 if retcode < 0:
496 raise RLException("command [%s] failed with exit code %s"%(cmd, retcode))
497 except OSError, e:
498 raise RLException("command [%s] failed: %s"%(cmd, e))
499
500
501
503 """
504 @raise RLException: if exectuable fails. Failure includes non-zero exit code.
505 """
506 exes = [e for e in config.executables if e.phase == PHASE_SETUP]
507 for e in exes:
508 self._launch_executable(config, e)
509
511 """
512 launch any core services that are not already running. master must
513 be already running
514 @raise RLException: if core launches fail
515 """
516 import roslib.names
517
518 master = config.master.get()
519 tolaunch = []
520 for node in config.nodes_core:
521 node_name = roslib.names.ns_join(node.namespace, node.name)
522 code, msg, _ = master.lookupNode(_ID, node_name)
523 if code == -1:
524 tolaunch.append(node)
525 elif code == 1:
526 print "core service [%s] found"%node_name
527 else:
528 print >> sys.stderr, "WARN: master is not behaving well (unexpected return value when looking up node)"
529 self.logger.error("ERROR: master return [%s][%s] on lookupNode call"%(code,msg))
530
531 for node in tolaunch:
532 node_name = roslib.names.ns_join(node.namespace, node.name)
533 name, success = self.launch_node(node, core=True)
534 if success:
535 print "started core service [%s]"%node_name
536 else:
537 raise RLException("failed to start core service [%s]"%node_name)
538
540 """
541 Launch a single node locally. Remote launching is handled separately by the remote module.
542 If node name is not assigned, one will be created for it.
543
544 @param node Node: node to launch
545 @param core bool: if True, core node
546 @return obj, bool: Process handle, successful launch. If success, return actual Process instance. Otherwise return name.
547 """
548 self.logger.info("... preparing to launch node of type [%s/%s]", node.package, node.type)
549
550
551
552
553 if node.machine is None:
554 node.machine = config.machines['']
555 if node.name is None:
556 node.name = roslib.names.anonymous_name(node.type)
557
558 master = config.master
559 import roslaunch.node_args
560 try:
561 process = create_node_process(self.run_id, node, master.uri)
562 except roslaunch.node_args.NodeParamsException, e:
563 self.logger.error(e)
564 if node.package == 'rosout' and node.type == 'rosout':
565 printerrlog("\n\n\nERROR: rosout is not built. Please run 'rosmake rosout'\n\n\n")
566 else:
567 printerrlog("ERROR: cannot launch node of type [%s/%s]: %s"%(node.package, node.type, str(e)))
568 if node.name:
569 return node.name, False
570 else:
571 return "%s/%s"%(node.package,node.type), False
572
573 self.logger.info("... created process [%s]", process.name)
574 if core:
575 self.pm.register_core_proc(process)
576 else:
577 self.pm.register(process)
578 node.process_name = process.name
579 self.logger.info("... registered process [%s]", process.name)
580
581
582 success = process.start()
583 if not success:
584 if node.machine.name:
585 printerrlog("launch of %s/%s on %s failed"%(node.package, node.type, node.machine.name))
586 else:
587 printerrlog("local launch of %s/%s failed"%(node.package, node.type))
588 else:
589 self.logger.info("... successfully launched [%s]", process.name)
590 return process, success
591
593 """
594 Check for running node process.
595 @param node Node: node object to check
596 @return bool: True if process associated with node is running (launched && !dead)
597 """
598
599 return node.process_name and self.pm.has_process(node.process_name)
600
602 """
603 Same as spin() but only does one cycle. must be run from the main thread.
604 """
605 if not self.pm:
606 return False
607 return self.pm.mainthread_spin_once()
608
610 """
611 spin() must be run from the main thread. spin() is very
612 important for roslaunch as it picks up jobs that the process
613 monitor need to be run in the main thread.
614 """
615 self.logger.info("spin")
616
617
618
619 if not self.pm or not self.pm.get_active_names():
620 printlog_bold("No processes to monitor")
621 self.stop()
622 return
623 self.pm.mainthread_spin()
624
625 self.logger.info("process monitor is done spinning, initiating full shutdown")
626 self.stop()
627 printlog_bold("done")
628
630 """
631 Stop the launch and all associated processes. not thread-safe.
632 """
633 self.logger.info("runner.stop()")
634 if self.pm is not None:
635 printlog("shutting down processing monitor...")
636 self.logger.info("shutting down processing monitor %s"%self.pm)
637 self.pm.shutdown()
638 self.pm.join()
639 self.pm = None
640 printlog("... shutting down processing monitor complete")
641 else:
642 self.logger.info("... roslaunch runner has already been stopped")
643
645 """
646 Setup the state of the ROS network, including the parameter
647 server state and core services
648 """
649
650 config.assign_machines()
651
652 if self.remote_runner:
653
654 self.remote_runner.add_process_listener(self.listeners)
655
656
657 self._launch_master(config)
658 self._launch_core_nodes(config)
659
660
661
662
663
664 self._launch_setup_executables(config)
665
666
667 self._load_parameters(config)
668
670 """
671 Run the launch. Depending on usage, caller should call
672 spin_once or spin as appropriate after launch().
673 @return ([str], [str]): tuple containing list of nodes that
674 successfully launches and list of nodes that failed to launch
675 @rtype: ([str], [str])
676 @raise RLException: if launch fails (e.g. run_id parameter does
677 not match ID on parameter server)
678 """
679 try:
680 self._setup(config)
681 succeeded, failed = self._launch_nodes(config)
682 return succeeded, failed
683 except KeyboardInterrupt:
684 self.stop()
685 raise
686
687
689 """
690 Run the test node. Blocks until completion or timeout.
691 @param test: test node to run
692 @type test: Test
693 @raise RLTestTimeoutException: if test fails to launch or test times out
694 """
695 self.logger.info("... preparing to run test [%s] of type [%s/%s]", test.test_name, test.package, test.type)
696 proc_h, success = self.launch_node(config, test)
697 if not success:
698 raise RLException("test [%s] failed to launch"%test.test_name)
699
700
701 timeout_t = time.time() + test.time_limit
702 pm = self.pm
703 while pm.mainthread_spin_once() and self.is_node_running(test):
704
705 if time.time() > timeout_t:
706 raise RLTestTimeoutException("test max time allotted")
707 time.sleep(0.1)
708
709
710
711
712
713
714
716 """
717 API for remote running
718 """
724 """
725 Listen to events about remote processes dying. Not
726 threadsafe. Must be called before processes started.
727 @param l: listener
728 @type l: L{ProcessListener}
729 """
730 pass
731
733 """
734 Contact each child to launch remote nodes
735 @return: succeeded, failed
736 @rtype: [str], [str]
737 """
738 pass
739