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 import os, shlex, subprocess
34 import socket
35 import types
36 import time
37 import signal
38
39 import roslib
40 import rospy
41 import threading
42 import xmlrpclib
43
44 import node_manager_fkie as nm
45 from common import get_ros_home, masteruri_from_ros, package_name
46 from supervised_popen import SupervisedPopen
51
53 ''' '''
54
59
61 return "BinarySelectionRequest from " + self.choices + "::" + repr(self.error)
62
63
64 CACHED_PKG_PATH = dict()
67 '''
68 This class contains the methods to run the nodes on local and remote machines
69 in a screen terminal.
70 '''
73
74 @classmethod
75 - def runNode(cls, node, launch_config, force2host=None, masteruri=None, auto_pw_request=False, user=None, pw=None, item=None):
76 '''
77 Start the node with given name from the given configuration.
78 @param node: the name of the node (with name space)
79 @type node: C{str}
80 @param launch_config: the configuration containing the node
81 @type launch_config: L{LaunchConfig}
82 @param force2host: start the node on given host.
83 @type force2host: L{str}
84 @param masteruri: force the masteruri.
85 @type masteruri: L{str}
86 @param auto_pw_request: opens question dialog directly, use True only if the method is called from the main GUI thread
87 @type auto_pw_request: bool
88 @raise StartException: if the screen is not available on host.
89 @raise Exception: on errors while resolving host
90 @see: L{node_manager_fkie.is_local()}
91 '''
92
93 n = launch_config.getNode(node)
94 if n is None:
95 raise StartException(''.join(["Node '", node, "' not found!"]))
96
97 env = list(n.env_args)
98 if n.respawn:
99
100 respawn_params = cls._get_respawn_params(rospy.names.ns_join(n.namespace, n.name), launch_config.Roscfg.params)
101 if respawn_params['max'] > 0:
102 env.append(('RESPAWN_MAX', '%d'%respawn_params['max']))
103 if respawn_params['min_runtime'] > 0:
104 env.append(('RESPAWN_MIN_RUNTIME', '%d'%respawn_params['min_runtime']))
105 if respawn_params['delay'] > 0:
106 env.append(('RESPAWN_DELAY', '%d'%respawn_params['delay']))
107 prefix = n.launch_prefix if not n.launch_prefix is None else ''
108 if prefix.lower() == 'screen' or prefix.lower().find('screen ') != -1:
109 rospy.loginfo("SCREEN prefix removed before start!")
110 prefix = ''
111 args = [''.join(['__ns:=', n.namespace.rstrip(rospy.names.SEP)]), ''.join(['__name:=', n.name])]
112 if not (n.cwd is None):
113 args.append(''.join(['__cwd:=', n.cwd]))
114
115
116 for remap in n.remap_args:
117 args.append(''.join([remap[0], ':=', remap[1]]))
118
119
120 host = launch_config.hostname
121 env_loader = ''
122 if n.machine_name:
123 machine = launch_config.Roscfg.machines[n.machine_name]
124 if not machine.address in ['localhost', '127.0.0.1']:
125 host = machine.address
126 if masteruri is None:
127 masteruri = nm.nameres().masteruri(n.machine_name)
128
129
130
131
132 if not force2host is None:
133 host = force2host
134
135
136 if masteruri is None:
137 masteruri = masteruri_from_ros()
138 env.append(('ROS_MASTER_URI', masteruri))
139
140 abs_paths = list()
141 not_found_packages = list()
142
143 if not masteruri is None and not masteruri in launch_config.global_param_done:
144 global_node_names = cls.getGlobalParams(launch_config.Roscfg)
145 rospy.loginfo("Register global parameter:\n %s", '\n '.join("%s%s"%(str(v)[:80],'...' if len(str(v))>80 else'') for v in global_node_names.values()))
146 abs_paths[len(abs_paths):], not_found_packages[len(not_found_packages):] = cls._load_parameters(masteruri, global_node_names, [], user, pw, auto_pw_request)
147 launch_config.global_param_done.append(masteruri)
148
149
150 if not masteruri is None:
151 nodens = ''.join([n.namespace, n.name, rospy.names.SEP])
152 params = dict()
153 for param, value in launch_config.Roscfg.params.items():
154 if param.startswith(nodens):
155 params[param] = value
156 clear_params = []
157 for cparam in launch_config.Roscfg.clear_params:
158 if cparam.startswith(nodens):
159 clear_params.append(cparam)
160 rospy.loginfo("Delete parameter:\n %s", '\n '.join(clear_params))
161 rospy.loginfo("Register parameter:\n %s", '\n '.join("%s%s"%(str(v)[:80],'...' if len(str(v))>80 else'') for v in params.values()))
162 abs_paths[len(abs_paths):], not_found_packages[len(not_found_packages):] = cls._load_parameters(masteruri, params, clear_params, user, pw, auto_pw_request)
163
164
165 if nm.is_local(host):
166 nm.screen().testScreen()
167 if item:
168 cmd_type = item
169 else:
170 try:
171 cmd = roslib.packages.find_node(n.package, n.type)
172 except (Exception, roslib.packages.ROSPkgException) as e:
173
174 raise StartException(''.join(["Can't find resource: ", str(e)]))
175
176 if isinstance(cmd, types.StringTypes):
177 cmd = [cmd]
178 cmd_type = ''
179 if cmd is None or len(cmd) == 0:
180 raise StartException(' '.join([n.type, 'in package [', n.package, '] not found!\n\nThe package was created?\nIs the binary executable?\n']))
181 if len(cmd) > 1:
182 if auto_pw_request:
183
184 try:
185 from python_qt_binding import QtGui
186 item, result = QtGui.QInputDialog.getItem(None, ' '.join(['Multiple executables', n.type, 'in', n.package]),
187 'Select an executable',
188 cmd, 0, False)
189 if result:
190
191 cmd_type = item
192 else:
193 return
194 except:
195 raise StartException('Multiple executables with same name in package found!')
196 else:
197 err = BinarySelectionRequest(cmd, 'Multiple executables')
198 raise nm.InteractionNeededError(err,
199 cls.runNode, (node, launch_config, force2host, masteruri, auto_pw_request, user, pw))
200 else:
201 cmd_type = cmd[0]
202
203 cwd = get_ros_home()
204 if not (n.cwd is None):
205 if n.cwd == 'ROS_HOME':
206 cwd = get_ros_home()
207 elif n.cwd == 'node':
208 cwd = os.path.dirname(cmd_type)
209 cls._prepareROSMaster(masteruri)
210 node_cmd = [nm.settings().respawn_script if n.respawn else '', prefix, cmd_type]
211 cmd_args = [nm.screen().getSceenCmd(node)]
212 cmd_args[len(cmd_args):] = node_cmd
213 cmd_args.append(str(n.args))
214 cmd_args[len(cmd_args):] = args
215 rospy.loginfo("RUN: %s", ' '.join(cmd_args))
216 new_env = dict(os.environ)
217 new_env['ROS_MASTER_URI'] = masteruri
218
219 if n.namespace:
220 new_env['ROS_NAMESPACE'] = n.namespace
221 for k, v in env:
222 new_env[k] = v
223 SupervisedPopen(shlex.split(str(' '.join(cmd_args))), cwd=cwd, env=new_env, id="Run node", description="Run node [%s]%s"%(str(n.package), str(n.type)))
224 else:
225
226
227 if launch_config.PackageName is None:
228 raise StartException(''.join(["Can't run remote without a valid package name!"]))
229
230 if prefix:
231 prefix = ''.join(['"', prefix, '"'])
232
233 env_command = ''
234 if env_loader:
235 rospy.logwarn("env_loader in machine tag currently not supported")
236 raise StartException("env_loader in machine tag currently not supported")
237 if env:
238 new_env = dict()
239 try:
240 for (k, v) in env:
241 v_value, is_abs_path, found, package = cls._resolve_abs_paths(v, host, user, pw, auto_pw_request)
242 new_env[k] = v_value
243 if is_abs_path:
244 abs_paths.append(('ENV', "%s=%s"%(k,v), "%s=%s"%(k,v_value)))
245 if not found and package:
246 not_found_packages.append(package)
247 env_command = "env "+' '.join(["%s=%s"%(k,v) for (k, v) in new_env.items()])
248 except nm.AuthenticationRequest as e:
249 raise nm.InteractionNeededError(e, cls.runNode, (node, launch_config, force2host, masteruri, auto_pw_request))
250
251 startcmd = [env_command, nm.settings().start_remote_script,
252 '--package', str(n.package),
253 '--node_type', str(n.type),
254 '--node_name', str(node),
255 '--node_respawn true' if n.respawn else '']
256 if not masteruri is None:
257 startcmd.append('--masteruri')
258 startcmd.append(masteruri)
259 if prefix:
260 startcmd[len(startcmd):] = ['--prefix', prefix]
261
262
263 node_args = []
264 try:
265 for a in n.args.split():
266 a_value, is_abs_path, found, package = cls._resolve_abs_paths(a, host, user, pw, auto_pw_request)
267 node_args.append(a_value)
268 if is_abs_path:
269 abs_paths.append(('ARGS', a, a_value))
270 if not found and package:
271 not_found_packages.append(package)
272
273 startcmd[len(startcmd):] = node_args
274 startcmd[len(startcmd):] = args
275 rospy.loginfo("Run remote on %s: %s", host, str(' '.join(startcmd)))
276
277 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, startcmd, user, pw, auto_pw_request, close_stdin=True)
278 output = stdout.read()
279 error = stderr.read()
280 stdout.close()
281 stderr.close()
282
283 except nm.AuthenticationRequest as e:
284 raise nm.InteractionNeededError(e, cls.runNode, (node, launch_config, force2host, masteruri, auto_pw_request))
285
286 if ok:
287 if error:
288 rospy.logwarn("ERROR while start '%s': %s", node, error)
289 raise StartException(str(''.join(['The host "', host, '" reports:\n', error])))
290 if output:
291 rospy.loginfo("STDOUT while start '%s': %s", node, output)
292
293 if len(abs_paths) > 0:
294 rospy.loginfo("Absolute paths found while start:\n%s", str('\n'.join([''.join([p, '\n OLD: ', ov, '\n NEW: ', nv]) for p, ov, nv in abs_paths])))
295
296 if len(not_found_packages) > 0:
297 packages = '\n'.join(not_found_packages)
298 raise StartException(str('\n'.join(['Some absolute paths are not renamed because following packages are not found on remote host:', packages])))
299
300
301
302
303
304
305 @classmethod
307 result = { 'max' : 0, 'min_runtime' : 0, 'delay': 0 }
308 respawn_max = rospy.names.ns_join(node, 'respawn/max')
309 respawn_min_runtime = rospy.names.ns_join(node, 'respawn/min_runtime')
310 respawn_delay = rospy.names.ns_join(node, 'respawn/delay')
311 try:
312 result['max'] = int(params[respawn_max].value)
313 except:
314 pass
315 try:
316 result['min_runtime'] = int(params[respawn_min_runtime].value)
317 except:
318 pass
319 try:
320 result['delay'] = int(params[respawn_delay].value)
321 except:
322 pass
323 return result
324
325 @classmethod
326 - def _load_parameters(cls, masteruri, params, clear_params, user, pw, auto_pw_request):
327 """
328 Load parameters onto the parameter server
329 """
330 import roslaunch
331 import roslaunch.launch
332 param_server = xmlrpclib.ServerProxy(masteruri)
333 p = None
334 abs_paths = list()
335 not_found_packages = list()
336 try:
337 socket.setdefaulttimeout(6+len(clear_params))
338
339 param_server_multi = xmlrpclib.MultiCall(param_server)
340
341
342
343 for p in clear_params:
344 param_server_multi.deleteParam(rospy.get_name(), p)
345 r = param_server_multi()
346 for code, msg, _ in r:
347 if code != 1 and not msg.find("is not set"):
348 rospy.logwarn("Failed to clear parameter: %s", msg)
349
350
351
352 socket.setdefaulttimeout(6+len(params))
353 param_server_multi = xmlrpclib.MultiCall(param_server)
354 for p in params.itervalues():
355
356 value, is_abs_path, found, package = cls._resolve_abs_paths(p.value, nm.nameres().address(masteruri), user, pw, auto_pw_request)
357 if is_abs_path:
358 abs_paths.append((p.key, p.value, value))
359 if not found and package:
360 not_found_packages.append(package)
361 if p.value is None:
362 rospy.logwarn("The parameter '%s' is invalid: '%s'"%(p.key, p.value))
363
364 else:
365 param_server_multi.setParam(rospy.get_name(), p.key, value if is_abs_path else p.value)
366 r = param_server_multi()
367 for code, msg, _ in r:
368 if code != 1:
369 raise StartException("Failed to set parameter: %s"%(msg))
370 except roslaunch.core.RLException, e:
371 raise StartException(e)
372 except Exception as e:
373 raise
374 finally:
375 socket.setdefaulttimeout(None)
376 return abs_paths, not_found_packages
377
378 @classmethod
380 '''
381 Replaces the local absolute path by remote absolute path. Only valid ROS
382 package paths are resolved.
383 @return: value, is absolute path, remote package found (ignore it on local host or if is not absolute path!), package name (if absolute path and remote package NOT found)
384 '''
385 if isinstance(value, types.StringTypes) and value.startswith('/') and (os.path.isfile(value) or os.path.isdir(value)):
386 if nm.is_local(host):
387 return value, True, True, ''
388 else:
389
390 path = os.path.dirname(value) if os.path.isfile(value) else value
391 package, package_path = package_name(path)
392 if package:
393 _, stdout, _, ok = nm.ssh().ssh_exec(host, ['rospack', 'find', package], user, pw, auto_pw_request, close_stdin=True, close_stderr=True)
394 output = stdout.read()
395 stdout.close()
396 if ok:
397 if output:
398
399
400 value.replace(package_path, output)
401
402 return value.replace(package_path, output.strip()), True, True, package
403 else:
404
405
406
407 pass
408 return value, True, False, ''
409 else:
410 return value, False, False, ''
411
412 @classmethod
413 - def runNodeWithoutConfig(cls, host, package, binary, name, args=[], masteruri=None, auto_pw_request=False, user=None, pw=None):
414 '''
415 Start a node with using a launch configuration.
416 @param host: the host or ip to run the node
417 @type host: C{str}
418 @param package: the ROS package containing the binary
419 @type package: C{str}
420 @param binary: the binary of the node to execute
421 @type binary: C{str}
422 @param name: the ROS name of the node (with name space)
423 @type name: C{str}
424 @param args: the list with arguments passed to the binary
425 @type args: C{[str, ...]}
426 @param auto_pw_request: opens question dialog directly, use True only if the method is called from the main GUI thread
427 @type auto_pw_request: bool
428 @raise Exception: on errors while resolving host
429 @see: L{node_manager_fkie.is_local()}
430 '''
431
432 args2 = list(args)
433 fullname = roslib.names.ns_join(roslib.names.SEP, name)
434 namespace = ''
435 for a in args:
436 if a.startswith('__ns:='):
437 namespace = a.replace('__ns:=', '')
438 fullname = roslib.names.ns_join(namespace, name)
439 args2.append(''.join(['__name:=', name]))
440
441 if nm.is_local(host):
442 try:
443 cmd = roslib.packages.find_node(package, binary)
444 except roslib.packages.ROSPkgException as e:
445
446 raise StartException(str(e))
447
448
449 if isinstance(cmd, types.StringTypes):
450 cmd = [cmd]
451 cmd_type = ''
452 if cmd is None or len(cmd) == 0:
453 raise StartException(' '.join([binary, 'in package [', package, '] not found!']))
454 if len(cmd) > 1:
455
456
457
458
459
460
461
462
463
464
465
466
467 err = [''.join(['Multiple executables with same name in package [', package, '] found:'])]
468 err.extend(cmd)
469 raise StartException('\n'.join(err))
470 else:
471 cmd_type = cmd[0]
472 cmd_str = str(' '.join([nm.screen().getSceenCmd(fullname), cmd_type, ' '.join(args2)]))
473 rospy.loginfo("Run without config: %s", cmd_str)
474 ps = None
475 new_env=dict(os.environ)
476 if namespace:
477 new_env['ROS_NAMESPACE'] = namespace
478 if not masteruri is None:
479 cls._prepareROSMaster(masteruri)
480 new_env['ROS_MASTER_URI'] = masteruri
481 SupervisedPopen(shlex.split(cmd_str), env=new_env, id="Run without config", description="Run without config [%s]%s"%(str(package), str(binary)))
482 else:
483
484 startcmd = [nm.settings().start_remote_script,
485 '--package', str(package),
486 '--node_type', str(binary),
487 '--node_name', str(fullname)]
488 startcmd[len(startcmd):] = args2
489 if not masteruri is None:
490 startcmd.append('--masteruri')
491 startcmd.append(masteruri)
492 rospy.loginfo("Run remote on %s: %s", host, ' '.join(startcmd))
493 try:
494 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, startcmd, user, pw, auto_pw_request, close_stdin=True)
495 if ok:
496 output = stdout.read()
497 error = stderr.read()
498 stdout.close()
499 stderr.close()
500 if error:
501 rospy.logwarn("ERROR while start '%s': %s", name, error)
502 raise StartException(''.join(['The host "', host, '" reports:\n', error]))
503
504
505
506
507 if output:
508 rospy.logdebug("STDOUT while start '%s': %s", name, output)
509 else:
510 if error:
511 rospy.logwarn("ERROR while start '%s': %s", name, error)
512 raise StartException(''.join(['The host "', host, '" reports:\n', error]))
513 except nm.AuthenticationRequest as e:
514 raise nm.InteractionNeededError(e, cls.runNodeWithoutConfig, (host, package, binary, name, args, masteruri, auto_pw_request))
515
516 @classmethod
518 if not masteruri:
519 masteruri = roslib.rosenv.get_master_uri()
520
521 try:
522 if not os.path.isdir(nm.ScreenHandler.LOG_PATH):
523 os.makedirs(nm.ScreenHandler.LOG_PATH)
524 socket.setdefaulttimeout(3)
525 master = xmlrpclib.ServerProxy(masteruri)
526 master.getUri(rospy.get_name())
527 except:
528
529
530
531
532 from urlparse import urlparse
533 master_host = urlparse(masteruri).hostname
534 if nm.is_local(master_host, True):
535 print "Start ROS-Master with", masteruri, "..."
536 master_port = urlparse(masteruri).port
537 new_env = dict(os.environ)
538 new_env['ROS_MASTER_URI'] = masteruri
539 cmd_args = '%s roscore --port %d'%(nm.ScreenHandler.getSceenCmd('/roscore--%d'%master_port), master_port)
540 print " %s"%cmd_args
541 try:
542 SupervisedPopen(shlex.split(cmd_args), env=new_env, id="ROSCORE", description="Start roscore")
543
544 result = -1
545 count = 1
546 while result == -1 and count < 11:
547 try:
548 print " retry connect to ROS master", count, '/', 10
549 master = xmlrpclib.ServerProxy(masteruri)
550 result, _, _ = master.getUri(rospy.get_name())
551 except:
552 time.sleep(1)
553 count += 1
554 if count >= 11:
555 raise StartException('Cannot connect to the ROS-Master: '+ str(masteruri))
556 except Exception as e:
557 import sys
558 print >> sys.stderr, e
559 raise
560 else:
561 raise Exception("ROS master '%s' is not reachable"%masteruri)
562 finally:
563 socket.setdefaulttimeout(None)
564
565 - def callService(self, service_uri, service, service_type, service_args=[]):
566 '''
567 Calls the service and return the response.
568 To call the service the ServiceProxy can't be used, because it uses
569 environment variables to determine the URI of the running service. In our
570 case this service can be running using another ROS master. The changes on the
571 environment variables is not thread safe.
572 So the source code of the rospy.SerivceProxy (tcpros_service.py) was modified.
573
574 @param service_uri: the URI of the service
575 @type service_uri: C{str}
576 @param service: full service name (with name space)
577 @type service: C{str}
578 @param service_type: service class
579 @type service_type: ServiceDefinition: service class
580 @param args: arguments
581 @return: the tuple of request and response.
582 @rtype: C{(request object, response object)}
583 @raise StartException: on error
584
585 @see: L{rospy.SerivceProxy}
586
587 '''
588 service = str(service)
589 rospy.loginfo("Call service %s[%s]: %s, %s", str(service), str(service_uri), str(service_type), str(service_args))
590 from rospy.core import parse_rosrpc_uri, is_shutdown
591
592 from rospy.exceptions import TransportInitError, TransportException
593 from rospy.impl.tcpros_base import TCPROSTransport, DEFAULT_BUFF_SIZE
594 from rospy.impl.tcpros_service import TCPROSServiceClient
595 from rospy.service import ServiceException
596 request = service_type._request_class()
597 import genpy
598 try:
599 now = rospy.get_rostime()
600 import std_msgs.msg
601 keys = { 'now': now, 'auto': std_msgs.msg.Header(stamp=now) }
602 genpy.message.fill_message_args(request, service_args, keys)
603 except genpy.MessageException as e:
604 def argsummary(args):
605 if type(args) in [tuple, list]:
606 return '\n'.join([' * %s (type %s)'%(a, type(a).__name__) for a in args])
607 else:
608 return ' * %s (type %s)'%(args, type(args).__name__)
609 raise StartException("Incompatible arguments to call service:\n%s\nProvided arguments are:\n%s\n\nService arguments are: [%s]"%(e, argsummary(service_args), genpy.message.get_printable_message_args(request)))
610
611
612 protocol = TCPROSServiceClient(service, service_type, headers={})
613 transport = TCPROSTransport(protocol, service)
614
615 dest_addr, dest_port = parse_rosrpc_uri(service_uri)
616
617 transport.buff_size = DEFAULT_BUFF_SIZE
618 try:
619 transport.connect(dest_addr, dest_port, service_uri, timeout=5)
620 except TransportInitError as e:
621
622 raise StartException(''.join(["unable to connect to service: ", str(e)]))
623 transport.send_message(request, 0)
624 try:
625 responses = transport.receive_once()
626 if len(responses) == 0:
627 raise StartException("service [%s] returned no response"%service)
628 elif len(responses) > 1:
629 raise StartException("service [%s] returned multiple responses: %s"%(service, len(responses)))
630 except TransportException as e:
631
632 if is_shutdown():
633 raise StartException("node shutdown interrupted service call")
634 else:
635 raise StartException("transport error completing service call: %s"%(str(e)))
636 except ServiceException, e:
637 raise StartException("Service error: %s"%(str(e)))
638 finally:
639 transport.close()
640 transport = None
641 return request, responses[0] if len(responses) > 0 else None
642
643
644 @classmethod
646 '''
647 Return the parameter of the configuration file, which are not associated with
648 any nodes in the configuration.
649 @param roscfg: the launch configuration
650 @type roscfg: L{roslaunch.ROSLaunchConfig}
651 @return: the list with names of the global parameter
652 @rtype: C{dict(param:value, ...)}
653 '''
654 result = dict()
655 nodes = []
656 for item in roscfg.resolved_node_names:
657 nodes.append(item)
658 for param, value in roscfg.params.items():
659 nodesparam = False
660 for n in nodes:
661 if param.startswith(n):
662 nodesparam = True
663 break
664 if not nodesparam:
665 result[param] = value
666 return result
667
668 @classmethod
670 if nm.is_local(host):
671 if len(nodes) == 1:
672 return nm.screen().getScreenLogFile(node=nodes[0])
673 else:
674 return nm.screen().LOG_PATH
675 else:
676 request = '[]' if len(nodes) != 1 else nodes[0]
677 try:
678 socket.setdefaulttimeout(3)
679 _, stdout, _, ok = nm.ssh().ssh_exec(host, [nm.settings().start_remote_script, '--ros_log_path', request], user, pw, auto_pw_request, close_stdin=True, close_stderr=True)
680 if ok:
681 output = stdout.read()
682 stdout.close()
683 return output
684 else:
685 raise StartException(str(''.join(['Get log path from "', host, '" failed:\n', error])))
686 except nm.AuthenticationRequest as e:
687 raise nm.InteractionNeededError(e, cls.copylogPath2Clipboards, (host, nodes, auto_pw_request))
688 finally:
689 socket.setdefaulttimeout(None)
690
691
692 @classmethod
693 - def openLog(cls, nodename, host, user=None):
694 '''
695 Opens the log file associated with the given node in a new terminal.
696 @param nodename: the name of the node (with name space)
697 @type nodename: C{str}
698 @param host: the host name or ip where the log file are
699 @type host: C{str}
700 @return: C{True}, if a log file was found
701 @rtype: C{bool}
702 @raise Exception: on errors while resolving host
703 @see: L{node_manager_fkie.is_local()}
704 '''
705 rospy.loginfo("show log for '%s' on '%s'", str(nodename), str(host))
706 title_opt = 'LOG %s on %s'%(nodename, host)
707 if nm.is_local(host):
708 found = False
709 screenLog = nm.screen().getScreenLogFile(node=nodename)
710 if os.path.isfile(screenLog):
711 cmd = nm.settings().terminal_cmd([nm.settings().log_viewer, screenLog], title_opt)
712 rospy.loginfo("open log: %s", cmd)
713 SupervisedPopen(shlex.split(cmd), id="Open log", description="Open log for '%s' on '%s'"%(str(nodename), str(host)))
714 found = True
715
716 roslog = nm.screen().getROSLogFile(nodename)
717 if os.path.isfile(roslog):
718 title_opt = title_opt.replace('LOG', 'ROSLOG')
719 cmd = nm.settings().terminal_cmd([nm.settings().log_viewer, roslog], title_opt)
720 rospy.loginfo("open ROS log: %s", cmd)
721 SupervisedPopen(shlex.split(cmd), id="Open log", description="Open log for '%s' on '%s'"%(str(nodename), str(host)))
722 found = True
723 return found
724 else:
725 ps = nm.ssh().ssh_x11_exec(host, [nm.settings().start_remote_script, '--show_screen_log', nodename], title_opt, user)
726 ps = nm.ssh().ssh_x11_exec(host, [nm.settings().start_remote_script, '--show_ros_log', nodename], title_opt.replace('LOG', 'ROSLOG'), user)
727 return False
728
729
730 @classmethod
731 - def deleteLog(cls, nodename, host, auto_pw_request=False, user=None, pw=None):
732 '''
733 Deletes the log file associated with the given node.
734 @param nodename: the name of the node (with name space)
735 @type nodename: C{str}
736 @param host: the host name or ip where the log file are to delete
737 @type host: C{str}
738 @raise Exception: on errors while resolving host
739 @see: L{node_manager_fkie.is_local()}
740 '''
741 rospy.loginfo("delete log for '%s' on '%s'", str(nodename), str(host))
742 if nm.is_local(host):
743 screenLog = nm.screen().getScreenLogFile(node=nodename)
744 pidFile = nm.screen().getScreenPidFile(node=nodename)
745 roslog = nm.screen().getROSLogFile(nodename)
746 if os.path.isfile(screenLog):
747 os.remove(screenLog)
748 if os.path.isfile(pidFile):
749 os.remove(pidFile)
750 if os.path.isfile(roslog):
751 os.remove(roslog)
752 else:
753 try:
754
755 nm.ssh().ssh_exec(host, [nm.settings().start_remote_script, '--delete_logs', nodename], user, pw, auto_pw_request, close_stdin=True, close_stdout=True, close_stderr=True)
756 except nm.AuthenticationRequest as e:
757 raise nm.InteractionNeededError(e, cls.deleteLog, (nodename, host, auto_pw_request))
758
759 - def kill(self, host, pid, auto_pw_request=False, user=None, pw=None):
760 '''
761 Kills the process with given process id on given host.
762 @param host: the name or address of the host, where the process must be killed.
763 @type host: C{str}
764 @param pid: the process id
765 @type pid: C{int}
766 @raise StartException: on error
767 @raise Exception: on errors while resolving host
768 @see: L{node_manager_fkie.is_local()}
769 '''
770 try:
771 self._kill_wo(host, pid, auto_pw_request, user, pw)
772 except nm.AuthenticationRequest as e:
773 raise nm.InteractionNeededError(e, self.kill, (host, pid, auto_pw_request))
774
775 - def _kill_wo(self, host, pid, auto_pw_request=False, user=None, pw=None):
776 rospy.loginfo("kill %s on %s", str(pid), host)
777 if nm.is_local(host):
778 os.kill(pid, signal.SIGKILL)
779 rospy.loginfo("kill: %s", str(pid))
780 else:
781
782 cmd = ['kill -9', str(pid)]
783 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, cmd, user, pw, False, close_stdin=True)
784 if ok:
785 output = stdout.read()
786 error = stderr.read()
787 stdout.close()
788 stderr.close()
789 if error:
790 rospy.logwarn("ERROR while kill %s: %s", str(pid), error)
791 raise StartException(str(''.join(['The host "', host, '" reports:\n', error])))
792 if output:
793 rospy.logdebug("STDOUT while kill %s on %s: %s", str(pid), host, output)
794
795 @classmethod
796 - def transfer_files(cls, host, path, auto_pw_request=False, user=None, pw=None):
797 '''
798 Copies the given file to the remote host. Uses caching of remote paths.
799 '''
800
801 if nm.is_local(host):
802
803 return
804 (pkg_name, pkg_path) = package_name(os.path.dirname(path))
805 if not pkg_name is None:
806
807 subfile_path = path.replace(pkg_path, '')
808
809 try:
810 output = ''
811 error = ''
812 ok = True
813 if CACHED_PKG_PATH.has_key(host) and CACHED_PKG_PATH[host].has_key(pkg_name):
814 output = CACHED_PKG_PATH[host][pkg_name]
815 else:
816 if not CACHED_PKG_PATH.has_key(host):
817 CACHED_PKG_PATH[host] = dict()
818 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, [nm.settings().start_remote_script, '--package', pkg_name], user, pw, auto_pw_request, close_stdin=True)
819 output = stdout.read()
820 error = stderr.read()
821 stdout.close()
822 stderr.close()
823 if ok:
824 if error:
825 rospy.logwarn("ERROR while transfer %s to %s: %s", path, host, error)
826 raise StartException(str(''.join(['The host "', host, '" reports:\n', error])))
827 if output:
828 CACHED_PKG_PATH[host][pkg_name] = output
829 nm.ssh().transfer(host, path, os.path.join(output.strip(), subfile_path.strip(os.sep)), user)
830 else:
831 raise StartException("Remote host no returned any answer. Is there the new version of node_manager installed?")
832 else:
833 raise StartException("Can't get path from remote host. Is there the new version of node_manager installed?")
834 except nm.AuthenticationRequest as e:
835 raise nm.InteractionNeededError(e, cls.transfer_files, (host, path, auto_pw_request))
836