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 """
37 rosnode implements the rosnode command-line tool and also provides a
38 library for retrieving ROS Node information.
39 """
40
41 from __future__ import print_function
42
43 import os
44 import errno
45 import sys
46 import socket
47 import time
48 import re
49 try:
50 from xmlrpc.client import ServerProxy
51 except ImportError:
52 from xmlrpclib import ServerProxy
53
54 try:
55 import urllib.parse as urlparse
56 except ImportError:
57 import urlparse
58
59 from optparse import OptionParser
60 import rosgraph
61 import rosgraph.names
62 import rostopic
63
64 NAME='rosnode'
65 ID = '/rosnode'
66
67 CONNECTION_PATTERN = re.compile(r'\w+ connection on port (\d+) to \[(.*) on socket (\d+)\]')
68
70 """
71 rosnode base exception type
72 """
73 pass
75 """
76 Exceptions for communication-related (i/o) errors, generally due to Master or Node network communication issues.
77 """
78 pass
79
80
82 code, msg, val = args
83 if code != 1:
84 raise ROSNodeException("remote call failed: %s"%msg)
85 return val
86
87 _caller_apis = {}
89 """
90 @param master: rosgraph Master instance
91 @type master: rosgraph.Master
92 @param caller_id: node name
93 @type caller_id: str
94 @param skip_cache: flag to skip cached data and force to lookup node from master
95 @type skip_cache: bool
96 @return: xmlrpc URI of caller_id
97 @rtype: str
98 @raise ROSNodeIOException: if unable to communicate with master
99 """
100 caller_api = _caller_apis.get(caller_id, None)
101 if not caller_api or skip_cache:
102 try:
103 caller_api = master.lookupNode(caller_id)
104 _caller_apis[caller_id] = caller_api
105 except rosgraph.MasterError:
106 return None
107 except socket.error:
108 raise ROSNodeIOException("Unable to communicate with master!")
109 return caller_api
110
112 for l in system_state[0:2]:
113 for entry in l:
114 if entry[0] == topic:
115 for n in entry[1]:
116 if rostopic.get_api(master, n) == uri:
117 return '%s (%s)' % (n, uri)
118 return uri
119
121 """
122 @param namespace: optional namespace to scope return values by. Namespace must already be resolved.
123 @type namespace: str
124 @return: list of node caller IDs
125 @rtype: [str]
126 @raise ROSNodeIOException: if unable to communicate with master
127 """
128 master = rosgraph.Master(ID)
129 try:
130 state = master.getSystemState()
131 except socket.error:
132 raise ROSNodeIOException("Unable to communicate with master!")
133 nodes = []
134 if namespace:
135
136 g_ns = rosgraph.names.make_global_ns(namespace)
137 for s in state:
138 for t, l in s:
139 nodes.extend([n for n in l if n.startswith(g_ns) or n == namespace])
140 else:
141 for s in state:
142 for t, l in s:
143 nodes.extend(l)
144 return list(set(nodes))
145
147 """
148 Find machines connected to nodes. This is a very costly procedure as it
149 must do N lookups with the Master, where N is the number of nodes.
150
151 @return: list of machines connected
152 @rtype: [str]
153 @raise ROSNodeIOException: if unable to communicate with master
154 """
155
156 master = rosgraph.Master(ID)
157
158
159
160
161 machines = []
162 node_names = get_node_names()
163 for n in node_names:
164 try:
165 uri = master.lookupNode(n)
166 h = urlparse.urlparse(uri).hostname
167 if h not in machines:
168 machines.append(h)
169
170 except socket.error:
171 raise ROSNodeIOException("Unable to communicate with master!")
172 except rosgraph.MasterError:
173
174 continue
175 return machines
176
177
179 """
180 Find nodes by machine name. This is a very costly procedure as it
181 must do N lookups with the Master, where N is the number of nodes.
182
183 @return: list of nodes on the specified machine
184 @rtype: [str]
185 @raise ROSNodeException: if machine name cannot be resolved to an address
186 @raise ROSNodeIOException: if unable to communicate with master
187 """
188
189 master = rosgraph.Master(ID)
190 try:
191 machine_actual = [host[4][0] for host in socket.getaddrinfo(machine, 0, 0, 0, socket.SOL_TCP)]
192 except:
193 raise ROSNodeException("cannot resolve machine name [%s] to address"%machine)
194
195
196
197
198 matches = [machine] + machine_actual
199 not_matches = []
200 node_names = get_node_names()
201 retval = []
202 for n in node_names:
203 try:
204 try:
205 uri = master.lookupNode(n)
206 except rosgraph.MasterError:
207
208 continue
209
210 h = urlparse.urlparse(uri).hostname
211 if h in matches:
212 retval.append(n)
213 elif h in not_matches:
214 continue
215 else:
216 r = [host[4][0] for host in socket.getaddrinfo(h, 0, 0, 0, socket.SOL_TCP)]
217 if set(r) & set(machine_actual):
218 matches.append(r)
219 retval.append(n)
220 else:
221 not_matches.append(r)
222 except socket.error:
223 raise ROSNodeIOException("Unable to communicate with master!")
224 return retval
225
227 """
228 Call shutdown on the specified nodes
229
230 @return: list of nodes that shutdown was called on successfully and list of failures
231 @rtype: ([str], [str])
232 """
233 master = rosgraph.Master(ID)
234
235 success = []
236 fail = []
237 tocall = []
238 try:
239
240 for n in node_names:
241 try:
242 uri = master.lookupNode(n)
243 tocall.append([n, uri])
244 except:
245 fail.append(n)
246 except socket.error:
247 raise ROSNodeIOException("Unable to communicate with master!")
248
249 for n, uri in tocall:
250
251
252 try:
253 p = ServerProxy(uri)
254 _succeed(p.shutdown(ID, 'user request'))
255 except:
256 pass
257 success.append(n)
258
259 return success, fail
260
262 """
263 Subroutine for rosnode_listnodes(). Composes list of strings to print to screen.
264
265 @param namespace: (default None) namespace to scope list to.
266 @type namespace: str
267 @param list_uri: (default False) return uris of nodes instead of names.
268 @type list_uri: bool
269 @param list_all: (default False) return names and uris of nodes as combined strings
270 @type list_all: bool
271 @return: new-line separated string containing list of all nodes
272 @rtype: str
273 """
274 master = rosgraph.Master(ID)
275 nodes = get_node_names(namespace)
276 nodes.sort()
277 if list_all:
278 return '\n'.join(["%s \t%s"%(get_api_uri(master, n) or 'unknown address', n) for n in nodes])
279 elif list_uri:
280 return '\n'.join([(get_api_uri(master, n) or 'unknown address') for n in nodes])
281 else:
282 return '\n'.join(nodes)
283
285 """
286 Print list of all ROS nodes to screen.
287
288 @param namespace: namespace to scope list to
289 @type namespace: str
290 @param list_uri: print uris of nodes instead of names
291 @type list_uri: bool
292 @param list_all: print node names and uris
293 @param list_all: bool
294 """
295 print(_sub_rosnode_listnodes(namespace=namespace, list_uri=list_uri, list_all=list_all))
296
297 -def rosnode_ping(node_name, max_count=None, verbose=False, skip_cache=False):
298 """
299 Test connectivity to node by calling its XMLRPC API
300 @param node_name: name of node to ping
301 @type node_name: str
302 @param max_count: number of ping requests to make
303 @type max_count: int
304 @param verbose: print ping information to screen
305 @type verbose: bool
306 @param skip_cache: flag to skip cached data and force to lookup from master
307 @type skip_cache: bool
308 @return: True if node pinged
309 @rtype: bool
310 @raise ROSNodeIOException: if unable to communicate with master
311 """
312 master = rosgraph.Master(ID)
313 node_api = get_api_uri(master, node_name, skip_cache=skip_cache)
314 if not node_api:
315 print("cannot ping [%s]: unknown node"%node_name, file=sys.stderr)
316 return False
317
318 timeout = 3.
319
320 if verbose:
321 print("pinging %s with a timeout of %ss"%(node_name, timeout))
322 socket.setdefaulttimeout(timeout)
323 node = ServerProxy(node_api)
324 lastcall = 0.
325 count = 0
326 acc = 0.
327 try:
328 while True:
329 try:
330 start = time.time()
331 pid = _succeed(node.getPid(ID))
332 end = time.time()
333
334 dur = (end-start)*1000.
335 acc += dur
336 count += 1
337
338 if verbose:
339 print("xmlrpc reply from %s\ttime=%fms"%(node_api, dur))
340
341 except socket.timeout:
342 print("connection to [%s] timed out"%node_name, file=sys.stderr)
343 return False
344 except socket.error as e:
345
346 try:
347
348 errnum, msg = e.args
349 if errnum == -2:
350 p = urlparse.urlparse(node_api)
351 print("ERROR: Unknown host [%s] for node [%s]"%(p.hostname, node_name), file=sys.stderr)
352 elif errnum == errno.ECONNREFUSED:
353
354 new_node_api = get_api_uri(master,node_name, skip_cache=True)
355 if not new_node_api:
356 print("cannot ping [%s]: unknown node"%node_name, file=sys.stderr)
357 return False
358 if new_node_api != node_api:
359 if verbose:
360 print("node url has changed from [%s] to [%s], retrying to ping"%(node_api, new_node_api))
361 node_api = new_node_api
362 node = ServerProxy(node_api)
363 continue
364 print("ERROR: connection refused to [%s]"%(node_api), file=sys.stderr)
365 else:
366 print("connection to [%s] failed"%node_name, file=sys.stderr)
367 return False
368 except ValueError:
369 print("unknown network error contacting node: %s"%(str(e)))
370 return False
371 if max_count and count >= max_count:
372 break
373 time.sleep(1.0)
374 except KeyboardInterrupt:
375 pass
376
377 if verbose and count > 1:
378 print("ping average: %fms"%(acc/count))
379 return True
380
382 """
383 Ping all running nodes
384 @return [str], [str]: pinged nodes, un-pingable nodes
385 @raise ROSNodeIOException: if unable to communicate with master
386 """
387 master = rosgraph.Master(ID)
388 try:
389 state = master.getSystemState()
390 except socket.error:
391 raise ROSNodeIOException("Unable to communicate with master!")
392
393 nodes = []
394 for s in state:
395 for t, l in s:
396 nodes.extend(l)
397 nodes = list(set(nodes))
398 if verbose:
399 print("Will ping the following nodes: \n"+''.join([" * %s\n"%n for n in nodes]))
400 pinged = []
401 unpinged = []
402 for node in nodes:
403 if rosnode_ping(node, max_count=1, verbose=verbose, skip_cache=skip_cache):
404 pinged.append(node)
405 else:
406 unpinged.append(node)
407 return pinged, unpinged
408
410 """
411 Remove registrations from ROS Master and node cache (_caller_apis) that match blacklist.
412 @param master: rosgraph Master instance
413 @type master: rosgraph.Master
414 @param blacklist: list of nodes to scrub
415 @type blacklist: [str]
416 """
417 pubs, subs, srvs = master.getSystemState()
418 for n in blacklist:
419 print("Unregistering", n)
420 node_api = get_api_uri(master, n)
421 for t, l in pubs:
422 if n in l:
423 master_n = rosgraph.Master(n)
424 master_n.unregisterPublisher(t, node_api)
425 for t, l in subs:
426 if n in l:
427 master_n = rosgraph.Master(n)
428 master_n.unregisterSubscriber(t, node_api)
429 for s, l in srvs:
430 if n in l:
431 service_api = master.lookupService(s)
432 master_n = rosgraph.Master(n)
433 master_n.unregisterService(s, service_api)
434 _caller_apis.pop(n, None)
435
437 """
438 Remove registrations from ROS Master that do not match whitelist.
439 @param master: rosgraph Master instance
440 @type master: rosgraph.Master
441 @param whitelist: list of nodes to keep
442 @type whitelist: list of nodes to keep
443 """
444 pubs, subs, srvs = master.getSystemState()
445 for t, l in pubs:
446 for n in l:
447 if n not in whitelist:
448 node_api = get_api_uri(master, n)
449 master_n = rosgraph.Master(n)
450 master_n.unregisterPublisher(t, node_api)
451 for t, l in subs:
452 for n in l:
453 if n not in whitelist:
454 node_api = get_api_uri(master, n)
455 master_n = rosgraph.Master(n)
456 master_n.unregisterSubscriber(t, node_api)
457 for s, l in srvs:
458 for n in l:
459 if n not in whitelist:
460 service_api = master.lookupService(s)
461 master_n = rosgraph.Master(n)
462 master_n.unregisterService(s, service_api)
463
465 """
466 This is a semi-hidden routine for cleaning up stale node
467 registration information on the ROS Master. The intent is to
468 remove this method once Master TTLs are properly implemented.
469 """
470 pinged, unpinged = rosnode_ping_all()
471 if unpinged:
472 master = rosgraph.Master(ID)
473 print("Unable to contact the following nodes:")
474 print('\n'.join(' * %s'%n for n in unpinged))
475 print("Warning: these might include alive and functioning nodes, e.g. in unstable networks.")
476 print("Cleanup will purge all information about these nodes from the master.")
477 print("Please type y or n to continue:")
478 input = sys.stdin.readline()
479 while not input.strip() in ['y', 'n']:
480 input = sys.stdin.readline()
481 if input.strip() == 'n':
482 print('aborting')
483 return
484
485 cleanup_master_blacklist(master, unpinged)
486
487 print("done")
488
490 def topic_type(t, pub_topics):
491 matches = [t_type for t_name, t_type in pub_topics if t_name == t]
492 if matches:
493 return matches[0]
494 return 'unknown type'
495
496 master = rosgraph.Master(ID)
497
498
499 try:
500 state = master.getSystemState()
501 pub_topics = master.getPublishedTopics('/')
502 except socket.error:
503 raise ROSNodeIOException("Unable to communicate with master!")
504 pubs = sorted([t for t, l in state[0] if node_name in l])
505 subs = sorted([t for t, l in state[1] if node_name in l])
506 srvs = sorted([t for t, l in state[2] if node_name in l])
507
508 buff = "Node [%s]"%node_name
509 if pubs:
510 buff += "\nPublications: \n"
511 buff += '\n'.join([" * %s [%s]"%(l, topic_type(l, pub_topics)) for l in pubs]) + '\n'
512 else:
513 buff += "\nPublications: None\n"
514 if subs:
515 buff += "\nSubscriptions: \n"
516 buff += '\n'.join([" * %s [%s]"%(l, topic_type(l, pub_topics)) for l in subs]) + '\n'
517 else:
518 buff += "\nSubscriptions: None\n"
519 if srvs:
520 buff += "\nServices: \n"
521 buff += '\n'.join([" * %s"%l for l in srvs]) + '\n'
522 else:
523 buff += "\nServices: None\n"
524
525 return buff
526
528
529 socket.setdefaulttimeout(5.0)
530 node = ServerProxy(node_api)
531 system_state = master.getSystemState()
532
533 try:
534 pid = _succeed(node.getPid(ID))
535 buff = "Pid: %s\n"%pid
536
537 businfo = _succeed(node.getBusInfo(ID))
538 if businfo:
539 buff += "Connections:\n"
540 for info in businfo:
541 dest_id = info[1]
542 direction = info[2]
543 transport = info[3]
544 topic = info[4]
545 if len(info) > 5:
546 connected = info[5]
547 else:
548 connected = True
549
550 if connected:
551 buff += " * topic: %s\n"%topic
552
553
554 buff += " * to: %s\n"%lookup_uri(master, system_state, topic, dest_id)
555 if direction == 'i':
556 buff += " * direction: inbound"
557 elif direction == 'o':
558 buff += " * direction: outbound"
559 else:
560 buff += " * direction: unknown"
561 if len(info) > 6:
562 match = CONNECTION_PATTERN.match(info[6])
563 if match is not None:
564 buff += " (%s - %s) [%s]" % match.groups()
565 buff += "\n"
566 buff += " * transport: %s\n"%transport
567 except socket.error:
568 raise ROSNodeIOException("Communication with node[%s] failed!"%(node_api))
569 return buff
570
572 """
573 Print information about node, including subscriptions and other debugging information. This will query the node over the network.
574
575 @param node_name: name of ROS node
576 @type node_name: str
577 @raise ROSNodeIOException: if unable to communicate with master
578 """
579 def topic_type(t, pub_topics):
580 matches = [t_type for t_name, t_type in pub_topics if t_name == t]
581 if matches:
582 return matches[0]
583 return 'unknown type'
584
585 master = rosgraph.Master(ID)
586 node_name = rosgraph.names.script_resolve_name('rosnode', node_name)
587
588 print('-'*80)
589 print(get_node_info_description(node_name))
590
591 node_api = get_api_uri(master, node_name)
592 if not node_api:
593 print("cannot contact [%s]: unknown node"%node_name, file=sys.stderr)
594 return
595
596 if not quiet:
597 print("\ncontacting node %s ..." % node_api)
598 print(get_node_connection_info_description(node_api, master))
599
600
601 rosnode_debugnode = rosnode_info
602
604 """
605 Implements rosnode 'list' command.
606 """
607 args = argv[2:]
608 parser = OptionParser(usage="usage: %prog list", prog=NAME)
609 parser.add_option("-u",
610 dest="list_uri", default=False,
611 action="store_true",
612 help="list XML-RPC URIs")
613 parser.add_option("-a","--all",
614 dest="list_all", default=False,
615 action="store_true",
616 help="list all information")
617 (options, args) = parser.parse_args(args)
618 namespace = None
619 if len(args) > 1:
620 parser.error("invalid args: you may only specify one namespace")
621 elif len(args) == 1:
622 namespace = rosgraph.names.script_resolve_name('rostopic', args[0])
623 rosnode_listnodes(namespace=namespace, list_uri=options.list_uri, list_all=options.list_all)
624
626 """
627 Implements rosnode 'info' command.
628 """
629 args = argv[2:]
630 parser = OptionParser(usage="usage: %prog info [options] node1 [node2...]",
631 prog=NAME)
632 parser.add_option("-q", "--quiet",
633 dest="quiet", default=False,
634 action="store_true",
635 help="Prints only basic information such as pubs/subs and does not contact nodes for more information")
636 (options, args) = parser.parse_args(args)
637 if not args:
638 parser.error("You must specify at least one node name")
639 for node in args:
640 rosnode_info(node, options.quiet)
641
643 """
644 Implements rosnode 'machine' command.
645
646 @raise ROSNodeException: if user enters in unrecognized machine name
647 """
648 args = argv[2:]
649 parser = OptionParser(usage="usage: %prog machine [machine-name]", prog=NAME)
650 (options, args) = parser.parse_args(args)
651 if len(args) > 1:
652 parser.error("please enter only one machine name")
653 elif len(args) == 0:
654 machines = get_machines_by_nodes()
655 machines.sort()
656 print('\n'.join(machines))
657 else:
658 nodes = get_nodes_by_machine(args[0])
659 nodes.sort()
660 print('\n'.join(nodes))
661
663 """
664 Implements rosnode 'kill' command.
665
666 @raise ROSNodeException: if user enters in unrecognized nodes
667 """
668 args = argv[2:]
669 parser = OptionParser(usage="usage: %prog kill [node]...", prog=NAME)
670 parser.add_option("-a","--all",
671 dest="kill_all", default=False,
672 action="store_true",
673 help="kill all nodes")
674
675 (options, args) = parser.parse_args(args)
676 if options.kill_all:
677 if args:
678 parser.error("invalid arguments with kill all (-a) option")
679 args = get_node_names()
680 args.sort()
681 elif not args:
682 node_list = get_node_names()
683 node_list.sort()
684 if not node_list:
685 print("No nodes running", file=sys.stderr)
686 return 0
687
688 sys.stdout.write('\n'.join(["%s. %s"%(i+1, n) for i,n in enumerate(node_list)]))
689 sys.stdout.write("\n\nPlease enter the number of the node you wish to kill.\n> ")
690 selection = ''
691 while not selection:
692 selection = sys.stdin.readline().strip()
693 try:
694 selection = int(selection)
695 if selection <= 0:
696 print("ERROR: invalid selection. Please enter a number (ctrl-C to cancel)")
697 except:
698 print("ERROR: please enter a number (ctrl-C to cancel)")
699 sys.stdout.flush()
700 selection = ''
701 args = [node_list[selection - 1]]
702 else:
703
704 args = [rosgraph.names.script_resolve_name(ID, n) for n in args]
705 node_list = get_node_names()
706 unknown = [n for n in args if not n in node_list]
707 if unknown:
708 raise ROSNodeException("Unknown node(s):\n"+'\n'.join([" * %s"%n for n in unknown]))
709 if len(args) > 1:
710 print("killing:\n"+'\n'.join([" * %s"%n for n in args]))
711 else:
712 print("killing %s"%(args[0]))
713
714 success, fail = kill_nodes(args)
715 if fail:
716 print("ERROR: Failed to kill:\n"+'\n'.join([" * %s"%n for n in fail]), file=sys.stderr)
717 return 1
718 print("killed")
719 return 0
720
722 """
723 Implements rosnode 'cleanup' command.
724 @param argv: command-line args
725 @type argv: [str]
726 """
727 args = argv[2:]
728 parser = OptionParser(usage="usage: %prog cleanup", prog=NAME)
729 (options, args) = parser.parse_args(args)
730 rosnode_cleanup()
731
733 """
734 Implements rosnode 'ping' command.
735 @param argv: command-line args
736 @type argv: [str]
737 """
738 args = argv[2:]
739 parser = OptionParser(usage="usage: %prog ping [options] <node>", prog=NAME)
740 parser.add_option("--all", "-a",
741 dest="ping_all", default=False,
742 action="store_true",
743 help="ping all nodes")
744 parser.add_option("-c",
745 dest="ping_count", default=None, metavar="COUNT",type="int",
746 help="number of pings to send. Not available with --all")
747 (options, args) = parser.parse_args(args)
748
749 node_name = None
750 if not options.ping_all:
751 if not args:
752 try:
753 parser.error("Please enter a node to ping. Available nodes are:\n"+_sub_rosnode_listnodes())
754 except:
755
756 parser.error("Please enter a node to ping")
757 elif len(args) > 1:
758 parser.error("you may only specify one input node")
759 elif len(args) == 1:
760 node_name = rosgraph.names.script_resolve_name('rosnode', args[0])
761 print("rosnode: node is [%s]"%node_name)
762 else:
763 if args:
764 parser.error("Invalid arguments '%s' used with --all"%(' '.join(args)))
765 elif options.ping_count:
766 parser.error("-c may not be used with --all")
767
768 if options.ping_all:
769 rosnode_ping_all(verbose=True)
770 else:
771 rosnode_ping(node_name, verbose=True, max_count=options.ping_count)
772
774 """
775 Prints rosnode usage information.
776 @param return_error whether to exit with error code os.EX_USAGE
777 """
778 print("""rosnode is a command-line tool for printing information about ROS Nodes.
779
780 Commands:
781 \trosnode ping\ttest connectivity to node
782 \trosnode list\tlist active nodes
783 \trosnode info\tprint information about node
784 \trosnode machine\tlist nodes running on a particular machine or list machines
785 \trosnode kill\tkill a running node
786 \trosnode cleanup\tpurge registration information of unreachable nodes
787
788 Type rosnode <command> -h for more detailed usage, e.g. 'rosnode ping -h'
789 """)
790 if return_error:
791 sys.exit(getattr(os, 'EX_USAGE', 1))
792 else:
793 sys.exit(0)
794
795 -def rosnodemain(argv=None):
796 """
797 Prints rosnode main entrypoint.
798 @param argv: override sys.argv
799 @param argv: [str]
800 """
801 if argv == None:
802 argv = sys.argv
803 if len(argv) == 1:
804 _fullusage()
805 try:
806 command = argv[1]
807 if command == 'ping':
808 sys.exit(_rosnode_cmd_ping(argv) or 0)
809 elif command == 'list':
810 sys.exit(_rosnode_cmd_list(argv) or 0)
811 elif command == 'info':
812 sys.exit(_rosnode_cmd_info(argv) or 0)
813 elif command == 'machine':
814 sys.exit(_rosnode_cmd_machine(argv) or 0)
815 elif command == 'cleanup':
816 sys.exit(_rosnode_cmd_cleanup(argv) or 0)
817 elif command == 'kill':
818 sys.exit(_rosnode_cmd_kill(argv) or 0)
819 elif command == '--help':
820 _fullusage(False)
821 else:
822 _fullusage()
823 except socket.error:
824 print("Network communication failed. Most likely failed to communicate with master.", file=sys.stderr)
825 sys.exit(1)
826 except rosgraph.MasterError as e:
827 print("ERROR: "+str(e), file=sys.stderr)
828 sys.exit(1)
829 except ROSNodeException as e:
830 print("ERROR: "+str(e), file=sys.stderr)
831 sys.exit(1)
832 except KeyboardInterrupt:
833 pass
834