Package node_manager_fkie :: Module start_handler
[frames] | no frames]

Source Code for Module node_manager_fkie.start_handler

  1  # Software License Agreement (BSD License) 
  2  # 
  3  # Copyright (c) 2012, Fraunhofer FKIE/US, Alexander Tiderko 
  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 Fraunhofer 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  import os 
 34  import roslib 
 35  import rospy 
 36  import shlex 
 37  import signal 
 38  import socket 
 39  import time 
 40  import types 
 41  import xmlrpclib 
 42   
 43  from master_discovery_fkie.common import get_hostname, get_port 
 44  from node_manager_fkie.common import get_ros_home, masteruri_from_ros, package_name 
 45  from node_manager_fkie.name_resolution import NameResolution 
 46  from node_manager_fkie.supervised_popen import SupervisedPopen 
 47   
 48  import node_manager_fkie as nm 
49 50 51 -class StartException(Exception):
52 pass
53
54 55 -class BinarySelectionRequest(Exception):
56 ''' ''' 57
58 - def __init__(self, choices, error):
59 Exception.__init__(self) 60 self.choices = choices 61 self.error = error
62
63 - def __str__(self):
64 return "BinarySelectionRequest from " + self.choices + "::" + repr(self.error)
65 66 67 CACHED_PKG_PATH = dict() # {host : {pkg: path}}
68 69 70 -class AdvRunCfg(object):
71
72 - def __init__(self, node, roslaunch_config, force2host=None, masteruri=None, executable=None, logging=None, auto_pw_request=False, user=None, pw=None):
73 ''' 74 @param force2host: start the node on given host. 75 @type force2host: str 76 @param masteruri: force the masteruri. 77 @type masteruri: str 78 ''' 79 self.node = node 80 self.roslaunch_config = roslaunch_config 81 self.force2host = force2host 82 self.masteruri = masteruri 83 self.logging = logging 84 self.executable = executable 85 self.auto_pw_request = auto_pw_request 86 self.user = user 87 self.pw = pw
88
89 90 -class StartHandler(object):
91 ''' 92 This class contains the methods to run the nodes on local and remote machines 93 in a screen terminal. 94 ''' 95
96 - def __init__(self):
97 pass
98 99 @classmethod
100 - def runNode(cls, runcfg):
101 ''' 102 Start the node with given name from the given configuration. 103 @param runcfg: the configuration containing the start parameter 104 @type runcfg: AdvRunCfg 105 @raise StartException: if the screen is not available on host. 106 @raise Exception: on errors while resolving host 107 @see: L{node_manager_fkie.is_local()} 108 ''' 109 # 'print "RUN node", node, time.time() 110 n = runcfg.roslaunch_config.getNode(runcfg.node) 111 if n is None: 112 raise StartException(''.join(["Node '", runcfg.node, "' not found!"])) 113 114 env = list(n.env_args) 115 # set logging options 116 if runcfg.logging is not None: 117 if not runcfg.logging.is_default('console_format'): 118 env.append(('ROSCONSOLE_FORMAT', '%s' % runcfg.logging.console_format)) 119 if n.respawn: 120 # set the respawn environment variables 121 respawn_params = cls._get_respawn_params(rospy.names.ns_join(n.namespace, n.name), runcfg.roslaunch_config.Roscfg.params) 122 if respawn_params['max'] > 0: 123 env.append(('RESPAWN_MAX', '%d' % respawn_params['max'])) 124 if respawn_params['min_runtime'] > 0: 125 env.append(('RESPAWN_MIN_RUNTIME', '%d' % respawn_params['min_runtime'])) 126 if respawn_params['delay'] > 0: 127 env.append(('RESPAWN_DELAY', '%d' % respawn_params['delay'])) 128 prefix = n.launch_prefix if n.launch_prefix is not None else '' 129 if prefix.lower() == 'screen' or prefix.lower().find('screen ') != -1: 130 rospy.loginfo("SCREEN prefix removed before start!") 131 prefix = '' 132 args = ['__ns:=%s' % n.namespace.rstrip(rospy.names.SEP), '__name:=%s' % n.name] 133 if n.cwd is not None: 134 args.append('__cwd:=%s' % n.cwd) 135 136 # add remaps 137 for remap in n.remap_args: 138 args.append(''.join([remap[0], ':=', remap[1]])) 139 140 # get host of the node 141 host = runcfg.roslaunch_config.hostname 142 env_loader = '' 143 if n.machine_name: 144 machine = runcfg.roslaunch_config.Roscfg.machines[n.machine_name] 145 if machine.address not in ['localhost', '127.0.0.1']: 146 host = machine.address 147 if runcfg.masteruri is None: 148 runcfg.masteruri = nm.nameres().masteruri(n.machine_name) 149 # TODO: env-loader support? 150 # if hasattr(machine, "env_loader") and machine.env_loader: 151 # env_loader = machine.env_loader 152 # set the host to the given host 153 if runcfg.force2host is not None: 154 host = runcfg.force2host 155 156 # set the ROS_MASTER_URI 157 if runcfg.masteruri is None: 158 runcfg.masteruri = masteruri_from_ros() 159 env.append(('ROS_MASTER_URI', runcfg.masteruri)) 160 ros_hostname = NameResolution.get_ros_hostname(runcfg.masteruri) 161 if ros_hostname: 162 env.append(('ROS_HOSTNAME', ros_hostname)) 163 164 abs_paths = list() # tuples of (parameter name, old value, new value) 165 not_found_packages = list() # package names 166 # set the global parameter 167 if runcfg.masteruri is not None and runcfg.masteruri not in runcfg.roslaunch_config.global_param_done: 168 global_node_names = cls.getGlobalParams(runcfg.roslaunch_config.Roscfg) 169 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())) 170 abs_paths[len(abs_paths):], not_found_packages[len(not_found_packages):] = cls._load_parameters(runcfg.masteruri, global_node_names, [], runcfg.user, runcfg.pw, runcfg.auto_pw_request) 171 runcfg.roslaunch_config.global_param_done.append(runcfg.masteruri) 172 173 # add params 174 if runcfg.masteruri is not None: 175 nodens = ''.join([n.namespace, n.name, rospy.names.SEP]) 176 params = dict() 177 for param, value in runcfg.roslaunch_config.Roscfg.params.items(): 178 if param.startswith(nodens): 179 params[param] = value 180 clear_params = [] 181 for cparam in runcfg.roslaunch_config.Roscfg.clear_params: 182 if cparam.startswith(nodens): 183 clear_params.append(cparam) 184 rospy.loginfo("Delete parameter:\n %s", '\n '.join(clear_params)) 185 rospy.loginfo("Register parameter:\n %s", '\n '.join("%s%s" % (str(v)[:80], '...' if len(str(v)) > 80 else'') for v in params.values())) 186 abs_paths[len(abs_paths):], not_found_packages[len(not_found_packages):] = cls._load_parameters(runcfg.masteruri, params, clear_params, runcfg.user, runcfg.pw, runcfg.auto_pw_request) 187 # 'print "RUN prepared", node, time.time() 188 189 if nm.is_local(host, wait=True): 190 nm.screen().testScreen() 191 if runcfg.executable: 192 cmd_type = runcfg.executable 193 else: 194 try: 195 cmd = roslib.packages.find_node(n.package, n.type) 196 except (Exception, roslib.packages.ROSPkgException) as starterr: 197 # multiple nodes, invalid package 198 raise StartException("Can't find resource: %s" % starterr) 199 # handle diferent result types str or array of string 200 if isinstance(cmd, types.StringTypes): 201 cmd = [cmd] 202 cmd_type = '' 203 if cmd is None or len(cmd) == 0: 204 raise StartException("%s in package [%s] not found!\n\nThe package " 205 "was created?\nIs the binary executable?\n" % (n.type, n.package)) 206 if len(cmd) > 1: 207 if runcfg.auto_pw_request: 208 # Open selection for executables, only if the method is called from the main GUI thread 209 try: 210 try: 211 from python_qt_binding.QtGui import QInputDialog 212 except: 213 from python_qt_binding.QtWidgets import QInputDialog 214 item, result = QInputDialog.getItem(None, 'Multiple executables %s in %s' % (n.type, n.package), 215 'Select an executable', 216 cmd, 0, False) 217 if result: 218 # open the selected screen 219 cmd_type = item 220 else: 221 return 222 except: 223 raise StartException('Multiple executables with same name in package found!') 224 else: 225 err = BinarySelectionRequest(cmd, 'Multiple executables') 226 raise nm.InteractionNeededError(err, cls.runNode, 227 (runcfg,)) 228 else: 229 cmd_type = cmd[0] 230 # determine the current working path, Default: the package of the node 231 cwd = get_ros_home() 232 if not (n.cwd is None): 233 if n.cwd == 'ROS_HOME': 234 cwd = get_ros_home() 235 elif n.cwd == 'node': 236 cwd = os.path.dirname(cmd_type) 237 cls._prepareROSMaster(runcfg.masteruri) 238 node_cmd = [nm.settings().respawn_script if n.respawn else '', prefix, cmd_type] 239 cmd_args = [nm.screen().getSceenCmd(runcfg.node)] 240 cmd_args[len(cmd_args):] = node_cmd 241 cmd_args.append(str(n.args)) 242 cmd_args[len(cmd_args):] = args 243 rospy.loginfo("RUN: %s", ' '.join(cmd_args)) 244 new_env = dict(os.environ) 245 new_env['ROS_MASTER_URI'] = runcfg.masteruri 246 ros_hostname = NameResolution.get_ros_hostname(runcfg.masteruri) 247 if ros_hostname: 248 new_env['ROS_HOSTNAME'] = ros_hostname 249 # add the namespace environment parameter to handle some cases, 250 # e.g. rqt_cpp plugins 251 if n.namespace: 252 new_env['ROS_NAMESPACE'] = n.namespace 253 # set logging options 254 if runcfg.logging is not None: 255 if not runcfg.logging.is_default('loglevel'): 256 env.append(('ROSCONSOLE_CONFIG_FILE', nm.settings().rosconsole_cfg_file(n.package))) 257 for key, value in env: 258 new_env[key] = value 259 SupervisedPopen(shlex.split(str(' '.join(cmd_args))), cwd=cwd, 260 env=new_env, object_id="Run node", description="Run node " 261 "[%s]%s" % (str(n.package), str(n.type))) 262 nm.filewatcher().add_binary(cmd_type, runcfg.node, runcfg.masteruri, runcfg.roslaunch_config.Filename) 263 else: 264 # 'print "RUN REMOTE", node, time.time() 265 # start remote 266 if runcfg.roslaunch_config.PackageName is None: 267 raise StartException("Can't run remote without a valid package name!") 268 # thus the prefix parameters while the transfer are not separated 269 if prefix: 270 prefix = ''.join(['"', prefix, '"']) 271 # setup environment 272 env_command = '' 273 if env_loader: 274 rospy.logwarn("env_loader in machine tag currently not supported") 275 raise StartException("env_loader in machine tag currently not supported") 276 if env: 277 new_env = dict() 278 try: 279 for (k, v) in env: 280 v_value, is_abs_path, found, package = cls._resolve_abs_paths(v, host, runcfg.user, runcfg.pw, runcfg.auto_pw_request) 281 new_env[k] = v_value 282 if is_abs_path: 283 abs_paths.append(('ENV', "%s=%s" % (k, v), "%s=%s" % (k, v_value))) 284 if not found and package: 285 not_found_packages.append(package) 286 env_command = "env " + ' '.join(["%s=\'%s\'" % (k, v) for (k, v) in new_env.items()]) 287 except nm.AuthenticationRequest as e: 288 raise nm.InteractionNeededError(e, cls.runNode, (runcfg,)) 289 290 startcmd = [env_command, nm.settings().start_remote_script, 291 '--package', str(n.package), 292 '--node_type', str(n.type), 293 '--node_name', str(runcfg.node), 294 '--node_respawn true' if n.respawn else ''] 295 if runcfg.masteruri is not None: 296 startcmd.append('--masteruri') 297 startcmd.append(runcfg.masteruri) 298 if prefix: 299 startcmd[len(startcmd):] = ['--prefix', prefix] 300 if runcfg.logging is not None: 301 if not runcfg.logging.is_default('loglevel'): 302 startcmd.append('--loglevel') 303 startcmd.append(nm.settings().logging.loglevel) 304 305 # rename the absolute paths in the args of the node 306 node_args = [] 307 try: 308 for a in n.args.split(): 309 a_value, is_abs_path, found, package = cls._resolve_abs_paths(a, host, runcfg.user, runcfg.pw, runcfg.auto_pw_request) 310 node_args.append(a_value) 311 if is_abs_path: 312 abs_paths.append(('ARGS', a, a_value)) 313 if not found and package: 314 not_found_packages.append(package) 315 316 startcmd[len(startcmd):] = node_args 317 startcmd[len(startcmd):] = args 318 rospy.loginfo("Run remote on %s: %s", host, str(' '.join(startcmd))) 319 # 'print "RUN CALL", node, time.time() 320 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, startcmd, runcfg.user, runcfg.pw, runcfg.auto_pw_request, close_stdin=True) 321 output = stdout.read() 322 error = stderr.read() 323 stdout.close() 324 stderr.close() 325 # 'print "RUN CALLOK", node, time.time() 326 except nm.AuthenticationRequest as e: 327 raise nm.InteractionNeededError(e, cls.runNode, (runcfg,)) 328 329 if ok: 330 if error: 331 rospy.logwarn("ERROR while start '%s': %s", runcfg.node, error) 332 raise StartException(str(''.join(['The host "', host, '" reports:\n', error]))) 333 if output: 334 rospy.loginfo("STDOUT while start '%s': %s", runcfg.node, output) 335 # inform about absolute paths in parameter value 336 if len(abs_paths) > 0: 337 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]))) 338 339 if len(not_found_packages) > 0: 340 packages = '\n'.join(not_found_packages) 341 raise StartException(str('\n'.join(['Some absolute paths are not renamed because following packages are not found on remote host:', packages])))
342 # if len(abs_paths) > 0: 343 # parameters = '\n'.join(abs_paths) 344 # raise nm.StartException(str('\n'.join(['Following parameter seems to use an absolute local path for remote host:', parameters, 'Use "cwd" attribute of the "node" tag to specify relative paths for remote usage!']))) 345 # 'print "RUN OK", node, time.time() 346 347 @classmethod
348 - def _get_respawn_params(cls, node, params):
349 result = {'max': 0, 'min_runtime': 0, 'delay': 0} 350 respawn_max = rospy.names.ns_join(node, 'respawn/max') 351 respawn_min_runtime = rospy.names.ns_join(node, 'respawn/min_runtime') 352 respawn_delay = rospy.names.ns_join(node, 'respawn/delay') 353 try: 354 result['max'] = int(params[respawn_max].value) 355 except: 356 pass 357 try: 358 result['min_runtime'] = int(params[respawn_min_runtime].value) 359 except: 360 pass 361 try: 362 result['delay'] = int(params[respawn_delay].value) 363 except: 364 pass 365 return result
366 367 @classmethod
368 - def _load_parameters(cls, masteruri, params, clear_params, user, pw, auto_pw_request):
369 """ 370 Load parameters onto the parameter server 371 """ 372 import roslaunch 373 import roslaunch.launch 374 param_server = xmlrpclib.ServerProxy(masteruri) 375 p = None 376 abs_paths = list() # tuples of (parameter name, old value, new value) 377 not_found_packages = list() # packages names 378 param_errors = [] 379 try: 380 socket.setdefaulttimeout(6 + len(clear_params)) 381 # multi-call style xmlrpc 382 param_server_multi = xmlrpclib.MultiCall(param_server) 383 384 # clear specified parameter namespaces 385 # #2468 unify clear params to prevent error 386 for p in clear_params: 387 param_server_multi.deleteParam(rospy.get_name(), p) 388 r = param_server_multi() 389 for code, msg, _ in r: 390 if code != 1 and not msg.find("is not set"): 391 rospy.logwarn("Failed to clear parameter: %s", msg) 392 # raise StartException("Failed to clear parameter: %s"%(msg)) 393 394 # multi-call objects are not reusable 395 socket.setdefaulttimeout(6 + len(params)) 396 param_server_multi = xmlrpclib.MultiCall(param_server) 397 for p in params.itervalues(): 398 # suppressing this as it causes too much spam 399 value, is_abs_path, found, package = cls._resolve_abs_paths(p.value, nm.nameres().address(masteruri), user, pw, auto_pw_request) 400 if is_abs_path: 401 abs_paths.append((p.key, p.value, value)) 402 if not found and package: 403 not_found_packages.append(package) 404 # if p.value is None: 405 # rospy.logwarn("The parameter '%s' is invalid: '%s'"%(p.key, p.value)) 406 # raise StartException("The parameter '%s' is invalid: '%s'"%(p.key, p.value)) 407 param_server_multi.setParam(rospy.get_name(), p.key, value if is_abs_path else p.value) 408 test_ret = cls._test_value(p.key, value if is_abs_path else p.value) 409 if test_ret: 410 param_errors.extend(test_ret) 411 r = param_server_multi() 412 for code, msg, _ in r: 413 if code != 1: 414 raise StartException("Failed to set parameter: %s" % (msg)) 415 except roslaunch.core.RLException, e: 416 raise StartException(e) 417 except Exception as e: 418 raise StartException("Failed to set parameter. ROS Parameter Server " 419 "reports: %s\n\n%s" % (e, '\n'.join(param_errors))) 420 finally: 421 socket.setdefaulttimeout(None) 422 return abs_paths, not_found_packages
423 424 @classmethod
425 - def _test_value(cls, key, value):
426 result = [] 427 if value is None: 428 msg = "Invalid parameter value of '%s': '%s'" % (key, value) 429 result.append(msg) 430 rospy.logwarn(msg) 431 elif isinstance(value, list): 432 for val in value: 433 ret = cls._test_value(key, val) 434 if ret: 435 result.extend(ret) 436 elif isinstance(value, dict): 437 for subkey, val in value.items(): 438 ret = cls._test_value("%s/%s" % (key, subkey), val) 439 if ret: 440 result.extend(ret) 441 return result
442 443 @classmethod
444 - def _resolve_abs_paths(cls, value, host, user, pw, auto_pw_request):
445 ''' 446 Replaces the local absolute path by remote absolute path. Only valid ROS 447 package paths are resolved. 448 @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) 449 ''' 450 if isinstance(value, types.StringTypes) and value.startswith('/') and (os.path.isfile(value) or os.path.isdir(value)): 451 if nm.is_local(host): 452 return value, True, True, '' 453 else: 454 path = os.path.dirname(value) if os.path.isfile(value) else value 455 package, package_path = package_name(path) 456 if package: 457 _, stdout, _, ok = nm.ssh().ssh_exec(host, ['rospack', 'find', package], user, pw, auto_pw_request, close_stdin=True, close_stderr=True) 458 output = stdout.read() 459 stdout.close() 460 if ok: 461 if output: 462 value.replace(package_path, output) 463 return value.replace(package_path, output.strip()), True, True, package 464 else: 465 # package on remote host not found! 466 # TODO add error message 467 # error = stderr.read() 468 pass 469 return value, True, False, '' 470 else: 471 return value, False, False, ''
472 473 @classmethod
474 - def runNodeWithoutConfig(cls, host, package, binary, name, args=[], masteruri=None, auto_pw_request=False, user=None, pw=None):
475 ''' 476 Start a node with using a launch configuration. 477 @param host: the host or ip to run the node 478 @type host: C{str} 479 @param package: the ROS package containing the binary 480 @type package: C{str} 481 @param binary: the binary of the node to execute 482 @type binary: C{str} 483 @param name: the ROS name of the node (with name space) 484 @type name: C{str} 485 @param args: the list with arguments passed to the binary 486 @type args: C{[str, ...]} 487 @param auto_pw_request: opens question dialog directly, use True only if the method is called from the main GUI thread 488 @type auto_pw_request: bool 489 @raise Exception: on errors while resolving host 490 @see: L{node_manager_fkie.is_local()} 491 ''' 492 # create the name with namespace 493 args2 = list(args) 494 fullname = roslib.names.ns_join(roslib.names.SEP, name) 495 namespace = '' 496 for a in args: 497 if a.startswith('__ns:='): 498 namespace = a.replace('__ns:=', '') 499 fullname = roslib.names.ns_join(namespace, name) 500 args2.append(''.join(['__name:=', name])) 501 # run on local host 502 if nm.is_local(host, wait=True): 503 try: 504 cmd = roslib.packages.find_node(package, binary) 505 except roslib.packages.ROSPkgException as e: 506 # multiple nodes, invalid package 507 raise StartException(str(e)) 508 # handle different result types str or array of string 509 # import types 510 if isinstance(cmd, types.StringTypes): 511 cmd = [cmd] 512 cmd_type = '' 513 if cmd is None or len(cmd) == 0: 514 raise StartException('%s in package [%s] not found!' % (binary, package)) 515 if len(cmd) > 1: 516 # Open selection for executables 517 err = [''.join(['Multiple executables with same name in package [', package, '] found:'])] 518 err.extend(cmd) 519 raise StartException('\n'.join(err)) 520 else: 521 cmd_type = cmd[0] 522 cmd_str = str(' '.join([nm.screen().getSceenCmd(fullname), cmd_type, ' '.join(args2)])) 523 rospy.loginfo("Run without config: %s", cmd_str) 524 new_env = dict(os.environ) 525 if namespace: 526 new_env['ROS_NAMESPACE'] = namespace 527 if masteruri is not None: 528 cls._prepareROSMaster(masteruri) 529 new_env['ROS_MASTER_URI'] = masteruri 530 ros_hostname = NameResolution.get_ros_hostname(masteruri) 531 if ros_hostname: 532 new_env['ROS_HOSTNAME'] = ros_hostname 533 SupervisedPopen(shlex.split(cmd_str), env=new_env, object_id="Run without config", description="Run without config [%s]%s" % (str(package), str(binary))) 534 else: 535 # run on a remote machine 536 startcmd = [nm.settings().start_remote_script, 537 '--package', str(package), 538 '--node_type', str(binary), 539 '--node_name', str(fullname)] 540 startcmd[len(startcmd):] = args2 541 if masteruri is not None: 542 startcmd.append('--masteruri') 543 startcmd.append(masteruri) 544 rospy.loginfo("Run remote on %s: %s", host, ' '.join(startcmd)) 545 try: 546 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, startcmd, user, pw, auto_pw_request, close_stdin=True) 547 if ok: 548 output = stdout.read() 549 error = stderr.read() 550 stdout.close() 551 stderr.close() 552 if error: 553 rospy.logwarn("ERROR while start '%s': %s", name, error) 554 raise StartException(''.join(['The host "', host, '" reports:\n', error])) 555 # from python_qt_binding import QtGui 556 # QtGui.QMessageBox.warning(None, 'Error while remote start %s'%str(name), 557 # str(''.join(['The host "', host, '" reports:\n', error])), 558 # QtGui.QMessageBox.Ok) 559 if output: 560 rospy.logdebug("STDOUT while start '%s': %s", name, output) 561 else: 562 if error: 563 rospy.logwarn("ERROR while start '%s': %s", name, error) 564 raise StartException(''.join(['The host "', host, '" reports:\n', error])) 565 except nm.AuthenticationRequest as e: 566 raise nm.InteractionNeededError(e, cls.runNodeWithoutConfig, (host, package, binary, name, args, masteruri, auto_pw_request))
567 568 @classmethod
569 - def _prepareROSMaster(cls, masteruri):
570 if masteruri is None: 571 masteruri = masteruri_from_ros() 572 # start roscore, if needed 573 try: 574 if not os.path.isdir(nm.ScreenHandler.LOG_PATH): 575 os.makedirs(nm.ScreenHandler.LOG_PATH) 576 socket.setdefaulttimeout(3) 577 master = xmlrpclib.ServerProxy(masteruri) 578 master.getUri(rospy.get_name()) 579 # restart ROSCORE on different masteruri?, not now... 580 # master_uri = master.getUri(rospy.get_name()) 581 # if masteruri != master_uri[2]: 582 # # kill the local roscore... 583 # raise 584 except: 585 # run a roscore 586 master_host = get_hostname(masteruri) 587 if nm.is_local(master_host, True): 588 master_port = get_port(masteruri) 589 new_env = dict(os.environ) 590 new_env['ROS_MASTER_URI'] = masteruri 591 ros_hostname = NameResolution.get_ros_hostname(masteruri) 592 if ros_hostname: 593 new_env['ROS_HOSTNAME'] = ros_hostname 594 cmd_args = '%s roscore --port %d' % (nm.ScreenHandler.getSceenCmd('/roscore--%d' % master_port), master_port) 595 try: 596 SupervisedPopen(shlex.split(cmd_args), env=new_env, object_id="ROSCORE", description="Start roscore") 597 # wait for roscore to avoid connection problems while init_node 598 result = -1 599 count = 1 600 while result == -1 and count < 11: 601 try: 602 master = xmlrpclib.ServerProxy(masteruri) 603 result, _, _ = master.getUri(rospy.get_name()) # _:=uri, msg 604 except: 605 time.sleep(1) 606 count += 1 607 if count >= 11: 608 raise StartException('Cannot connect to the ROS-Master: ' + str(masteruri)) 609 except Exception as e: 610 raise Exception("Error while call '%s': %s" % (cmd_args, e)) 611 else: 612 raise Exception("ROS master '%s' is not reachable" % masteruri) 613 finally: 614 socket.setdefaulttimeout(None)
615
616 - def callService(self, service_uri, service, service_type, service_args=[]):
617 ''' 618 Calls the service and return the response. 619 To call the service the ServiceProxy can't be used, because it uses 620 environment variables to determine the URI of the running service. In our 621 case this service can be running using another ROS master. The changes on the 622 environment variables is not thread safe. 623 So the source code of the rospy.SerivceProxy (tcpros_service.py) was modified. 624 625 @param service_uri: the URI of the service 626 @type service_uri: C{str} 627 @param service: full service name (with name space) 628 @type service: C{str} 629 @param service_type: service class 630 @type service_type: ServiceDefinition: service class 631 @param service_args: arguments 632 @return: the tuple of request and response. 633 @rtype: C{(request object, response object)} 634 @raise StartException: on error 635 636 @see: U{rospy.SerivceProxy<http://docs.ros.org/kinetic/api/rospy/html/rospy.impl.tcpros_service.ServiceProxy-class.html>} 637 638 ''' 639 service = str(service) 640 rospy.loginfo("Call service %s[%s]: %s, %s", str(service), str(service_uri), str(service_type), str(service_args)) 641 from rospy.core import parse_rosrpc_uri, is_shutdown 642 # from rospy.msg import args_kwds_to_message 643 from rospy.exceptions import TransportInitError, TransportException 644 from rospy.impl.tcpros_base import TCPROSTransport, DEFAULT_BUFF_SIZE # ,TCPROSTransportProtocol 645 from rospy.impl.tcpros_service import TCPROSServiceClient 646 from rospy.service import ServiceException 647 request = service_type._request_class() 648 import genpy 649 try: 650 now = rospy.get_rostime() 651 import std_msgs.msg 652 keys = {'now': now, 'auto': std_msgs.msg.Header(stamp=now)} 653 genpy.message.fill_message_args(request, service_args, keys) 654 except genpy.MessageException as e: 655 def argsummary(args): 656 if type(args) in [tuple, list]: 657 return '\n'.join([' * %s (type %s)' % (a, type(a).__name__) for a in args]) 658 else: 659 return ' * %s (type %s)' % (args, type(args).__name__)
660 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))) 661 662 # request = args_kwds_to_message(type._request_class, args, kwds) 663 protocol = TCPROSServiceClient(service, service_type, headers={}) 664 transport = TCPROSTransport(protocol, service) 665 # initialize transport 666 dest_addr, dest_port = parse_rosrpc_uri(service_uri) 667 # connect to service 668 transport.buff_size = DEFAULT_BUFF_SIZE 669 try: 670 transport.connect(dest_addr, dest_port, service_uri, timeout=5) 671 except TransportInitError as e: 672 # can be a connection or md5sum mismatch 673 raise StartException(''.join(["unable to connect to service: ", str(e)])) 674 transport.send_message(request, 0) 675 try: 676 responses = transport.receive_once() 677 if len(responses) == 0: 678 raise StartException("service [%s] returned no response" % service) 679 elif len(responses) > 1: 680 raise StartException("service [%s] returned multiple responses: %s" % (service, len(responses))) 681 except TransportException as e: 682 # convert lower-level exception to exposed type 683 if is_shutdown(): 684 raise StartException("node shutdown interrupted service call") 685 else: 686 raise StartException("transport error completing service call: %s" % (str(e))) 687 except ServiceException, e: 688 raise StartException("Service error: %s" % (str(e))) 689 finally: 690 transport.close() 691 transport = None 692 return request, responses[0] if len(responses) > 0 else None
693 694 @classmethod
695 - def getGlobalParams(cls, roscfg):
696 ''' 697 Return the parameter of the configuration file, which are not associated with 698 any nodes in the configuration. 699 @param roscfg: the launch configuration 700 @type roscfg: U{roslaunch.ROSLaunchConfig<http://docs.ros.org/kinetic/api/roslaunch/html/>} 701 @return: the list with names of the global parameter 702 @rtype: C{dict(param:value, ...)} 703 ''' 704 result = dict() 705 nodes = [] 706 for item in roscfg.resolved_node_names: 707 nodes.append(item) 708 for param, value in roscfg.params.items(): 709 nodesparam = False 710 for n in nodes: 711 if param.startswith(n): 712 nodesparam = True 713 break 714 if not nodesparam: 715 result[param] = value 716 return result
717 718 @classmethod
719 - def get_log_path(cls, host, nodes=[], auto_pw_request=False, user=None, pw=None):
720 if nm.is_local(host): 721 if len(nodes) == 1: 722 return nm.screen().getScreenLogFile(node=nodes[0]) 723 else: 724 return nm.screen().LOG_PATH 725 else: 726 request = '[]' if len(nodes) != 1 else nodes[0] 727 try: 728 socket.setdefaulttimeout(3) 729 _, 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) 730 if ok: 731 output = stdout.read() 732 stdout.close() 733 return output.strip() 734 else: 735 raise StartException(str(''.join(['Get log path from "', host, '" failed']))) 736 except nm.AuthenticationRequest as e: 737 raise nm.InteractionNeededError(e, cls.get_log_path, (host, nodes, auto_pw_request)) 738 finally: 739 socket.setdefaulttimeout(None)
740 741 @classmethod
742 - def openLog(cls, nodename, host, user=None, only_screen=False):
743 ''' 744 Opens the log file associated with the given node in a new terminal. 745 @param nodename: the name of the node (with name space) 746 @type nodename: C{str} 747 @param host: the host name or ip where the log file are 748 @type host: C{str} 749 @return: C{True}, if a log file was found 750 @rtype: C{bool} 751 @raise Exception: on errors while resolving host 752 @see: L{node_manager_fkie.is_local()} 753 ''' 754 rospy.loginfo("show log for '%s' on '%s'", str(nodename), str(host)) 755 title_opt = 'LOG %s on %s' % (nodename, host) 756 if nm.is_local(host): 757 found = False 758 screenLog = nm.screen().getScreenLogFile(node=nodename) 759 if os.path.isfile(screenLog): 760 cmd = nm.settings().terminal_cmd([nm.settings().log_viewer, screenLog], title_opt) 761 rospy.loginfo("open log: %s", cmd) 762 SupervisedPopen(shlex.split(cmd), object_id="Open log", description="Open log for '%s' on '%s'" % (str(nodename), str(host))) 763 found = True 764 # open roslog file 765 roslog = nm.screen().getROSLogFile(nodename) 766 if os.path.isfile(roslog) and not only_screen: 767 title_opt = title_opt.replace('LOG', 'ROSLOG') 768 cmd = nm.settings().terminal_cmd([nm.settings().log_viewer, roslog], title_opt) 769 rospy.loginfo("open ROS log: %s", cmd) 770 SupervisedPopen(shlex.split(cmd), object_id="Open log", description="Open log for '%s' on '%s'" % (str(nodename), str(host))) 771 found = True 772 return found 773 else: 774 ps = nm.ssh().ssh_x11_exec(host, [nm.settings().start_remote_script, '--show_screen_log', nodename], title_opt, user) 775 if not only_screen: 776 ps = nm.ssh().ssh_x11_exec(host, [nm.settings().start_remote_script, '--show_ros_log', nodename], title_opt.replace('LOG', 'ROSLOG'), user) 777 return False
778 779 @classmethod
780 - def deleteLog(cls, nodename, host, auto_pw_request=False, user=None, pw=None):
781 ''' 782 Deletes the log file associated with the given node. 783 @param nodename: the name of the node (with name space) 784 @type nodename: C{str} 785 @param host: the host name or ip where the log file are to delete 786 @type host: C{str} 787 @raise Exception: on errors while resolving host 788 @see: L{node_manager_fkie.is_local()} 789 ''' 790 rospy.loginfo("delete log for '%s' on '%s'", str(nodename), str(host)) 791 if nm.is_local(host): 792 screenLog = nm.screen().getScreenLogFile(node=nodename) 793 pidFile = nm.screen().getScreenPidFile(node=nodename) 794 roslog = nm.screen().getROSLogFile(nodename) 795 if os.path.isfile(screenLog): 796 os.remove(screenLog) 797 if os.path.isfile(pidFile): 798 os.remove(pidFile) 799 if os.path.isfile(roslog): 800 os.remove(roslog) 801 else: 802 try: 803 # output ignored: output, error, ok 804 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) 805 except nm.AuthenticationRequest as e: 806 raise nm.InteractionNeededError(e, cls.deleteLog, (nodename, host, auto_pw_request))
807
808 - def kill(self, host, pid, auto_pw_request=False, user=None, pw=None):
809 ''' 810 Kills the process with given process id on given host. 811 @param host: the name or address of the host, where the process must be killed. 812 @type host: C{str} 813 @param pid: the process id 814 @type pid: C{int} 815 @raise StartException: on error 816 @raise Exception: on errors while resolving host 817 @see: L{node_manager_fkie.is_local()} 818 ''' 819 try: 820 self._kill_wo(host, pid, auto_pw_request, user, pw) 821 except nm.AuthenticationRequest as e: 822 raise nm.InteractionNeededError(e, self.kill, (host, pid, auto_pw_request))
823
824 - def _kill_wo(self, host, pid, auto_pw_request=False, user=None, pw=None):
825 rospy.loginfo("kill %s on %s", str(pid), host) 826 if nm.is_local(host): 827 os.kill(pid, signal.SIGKILL) 828 rospy.loginfo("kill: %s", str(pid)) 829 else: 830 # kill on a remote machine 831 cmd = ['kill -9', str(pid)] 832 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, cmd, user, pw, False, close_stdin=True) 833 if ok: 834 output = stdout.read() 835 error = stderr.read() 836 stdout.close() 837 stderr.close() 838 if error: 839 rospy.logwarn("ERROR while kill %s: %s", str(pid), error) 840 raise StartException(str(''.join(['The host "', host, '" reports:\n', error]))) 841 if output: 842 rospy.logdebug("STDOUT while kill %s on %s: %s", str(pid), host, output)
843
844 - def killall_roscore(self, host, auto_pw_request=False, user=None, pw=None):
845 ''' 846 Kills all roscore processes on given host. 847 @param host: the name or address of the host, where the process must be killed. 848 @type host: C{str} 849 @raise StartException: on error 850 @raise Exception: on errors while resolving host 851 @see: L{node_manager_fkie.is_local()} 852 ''' 853 try: 854 self._killall_roscore_wo(host, auto_pw_request, user, pw) 855 except nm.AuthenticationRequest as e: 856 raise nm.InteractionNeededError(e, self.killall_roscore, (host, auto_pw_request))
857
858 - def _killall_roscore_wo(self, host, auto_pw_request=False, user=None, pw=None):
859 rospy.loginfo("killall roscore on %s", host) 860 cmd = ['killall', 'roscore'] 861 if nm.is_local(host): 862 SupervisedPopen(cmd, object_id="killall roscore", description="killall roscore") 863 else: 864 # kill on a remote machine 865 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, cmd, user, pw, False, close_stdin=True) 866 if ok: 867 output = stdout.read() 868 error = stderr.read() 869 stdout.close() 870 stderr.close() 871 if error: 872 rospy.logwarn("ERROR while killall roscore on %s: %s" % (host, error)) 873 raise StartException('The host "%s" reports:\n%s' % (host, error)) 874 if output: 875 rospy.logdebug("STDOUT while killall roscore on %s: %s" % (host, output))
876
877 - def poweroff(self, host, auto_pw_request=False, user=None, pw=None):
878 ''' 879 poweroff given host. 880 @param host: the name or address of the host, where the process must be killed. 881 @type host: C{str} 882 @raise StartException: on error 883 @raise Exception: on errors while resolving host 884 @see: L{node_manager_fkie.is_local()} 885 ''' 886 try: 887 self._poweroff_wo(host, auto_pw_request, user, pw) 888 except nm.AuthenticationRequest as e: 889 raise nm.InteractionNeededError(e, self.poweroff, (host, auto_pw_request))
890
891 - def _poweroff_wo(self, host, auto_pw_request=False, user=None, pw=None):
892 if nm.is_local(host): 893 rospy.logwarn("shutdown localhost localhost!") 894 cmd = nm.settings().terminal_cmd(['sudo poweroff'], "poweroff") 895 SupervisedPopen(shlex.split(cmd), object_id="poweroff", description="poweroff") 896 else: 897 rospy.loginfo("poweroff %s", host) 898 # kill on a remote machine 899 cmd = ['sudo poweroff'] 900 _ = nm.ssh().ssh_x11_exec(host, cmd, 'Shutdown %s' % host, user)
901 902 @classmethod
903 - def transfer_files(cls, host, path, auto_pw_request=False, user=None, pw=None):
904 ''' 905 Copies the given file to the remote host. Uses caching of remote paths. 906 ''' 907 # get package of the file 908 if nm.is_local(host): 909 # it's local -> no copy needed 910 return 911 (pkg_name, pkg_path) = package_name(os.path.dirname(path)) 912 if pkg_name is not None: 913 # get the subpath of the file 914 subfile_path = path.replace(pkg_path, '') 915 # get the path of the package on the remote machine 916 try: 917 output = '' 918 error = '' 919 ok = True 920 if host in CACHED_PKG_PATH and pkg_name in CACHED_PKG_PATH[host]: 921 output = CACHED_PKG_PATH[host][pkg_name] 922 else: 923 if host not in CACHED_PKG_PATH: 924 CACHED_PKG_PATH[host] = dict() 925 _, stdout, stderr, ok = nm.ssh().ssh_exec(host, [nm.settings().start_remote_script, '--package', pkg_name], user, pw, auto_pw_request, close_stdin=True) 926 output = stdout.read() 927 error = stderr.read() 928 stdout.close() 929 stderr.close() 930 if ok: 931 if error: 932 rospy.logwarn("ERROR while transfer %s to %s: %s", path, host, error) 933 raise StartException(str(''.join(['The host "', host, '" reports:\n', error]))) 934 if output: 935 CACHED_PKG_PATH[host][pkg_name] = output 936 nm.ssh().transfer(host, path, os.path.join(output.strip(), subfile_path.strip(os.sep)), user) 937 else: 938 raise StartException("Remote host no returned any answer. Is there the new version of node_manager installed?") 939 else: 940 raise StartException("Can't get path from remote host. Is there the new version of node_manager installed?") 941 except nm.AuthenticationRequest as e: 942 raise nm.InteractionNeededError(e, cls.transfer_files, (host, path, auto_pw_request))
943 944 @classmethod
945 - def ntpdate(cls, host, cmd, user=None, pw=None):
946 ''' 947 Opens the log file associated with the given node in a new terminal. 948 @param host: the host name or ip where the log file are 949 @type host: C{str} 950 @param cmd: command to set the time 951 @type cmd: C{str} 952 @return: C{True}, if a log file was found 953 @rtype: C{bool} 954 @raise Exception: on errors while resolving host 955 @see: L{node_manager_fkie.is_local()} 956 ''' 957 mesg = "synchronize time on '%s' using '%s'" % (str(host), cmd) 958 rospy.loginfo(mesg) 959 title_opt = "ntpdate on %s" % str(host) # '%s on %s' % (cmd, host) 960 if nm.is_local(host): 961 cmd = nm.settings().terminal_cmd([cmd], title_opt, noclose=True) 962 rospy.loginfo("EXEC: %s" % cmd) 963 ps = SupervisedPopen(shlex.split(cmd), object_id=cmd, description=mesg) 964 else: 965 ps = nm.ssh().ssh_x11_exec(host, [cmd, ';echo "";echo "this terminal will be closed in 10 sec...";sleep 10'], title_opt, user) 966 return False
967