| Home | Trees | Indices | Help |
|---|
|
|
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 time
34 import socket
35 import threading
36 import xmlrpclib
37 import random
38 from python_qt_binding import QtCore
39
40 #import roslib; roslib.load_manifest('node_manager_fkie')
41 import rospy
42
43 from master_discovery_fkie.master_info import MasterInfo
44
46 '''
47 A thread to retrieve the state about ROS master from remote discovery node and
48 publish it be sending a QT signal.
49 '''
50 update_signal = QtCore.Signal(MasterInfo)
51 '''
52 @ivar: update_signal is a signal, which is emitted, if a new
53 L{aster_discovery_fkie.MasterInfo} is retrieved.
54 '''
55
56 error_signal = QtCore.Signal(str, str)
57 '''
58 @ivar: error_signal is a signal (masteruri, error message), which is emitted,
59 if an error while retrieving a master info was occurred.
60 '''
61
63 '''
64 @param masteruri: the URI of the remote ROS master
65 @type masteruri: C{str}
66 @param monitoruri: the URI of the monitor RPC interface of the master_discovery node
67 @type monitoruri: C{str}
68 @param delayed_exec: Delay the execution of the request for given seconds.
69 @type delayed_exec: C{float}
70 '''
71 QtCore.QObject.__init__(self)
72 threading.Thread.__init__(self)
73 self._monitoruri = monitoruri
74 self._masteruri = masteruri
75 self._delayed_exec = delayed_exec
76 self.setDaemon(True)
77
79 '''
80 '''
81 try:
82 delay = self._delayed_exec+0.5+random.random()
83 #'print "wait request update", self._monitoruri, delay
84 time.sleep(delay)
85 #'print "request update", self._monitoruri
86 socket.setdefaulttimeout(25)
87 remote_monitor = xmlrpclib.ServerProxy(self._monitoruri)
88 remote_info = remote_monitor.masterInfo()
89 master_info = MasterInfo.from_list(remote_info)
90 master_info.check_ts = time.time()
91 #'print "request success", self._monitoruri
92 self.update_signal.emit(master_info)
93 except:
94 import traceback
95 # print traceback.print_exc()
96 formatted_lines = traceback.format_exc().splitlines()
97 rospy.logwarn("Connection to %s failed:\n\t%s", str(self._monitoruri), formatted_lines[-1])
98 #'print "request failed", self._monitoruri
99 self.error_signal.emit(self._masteruri, formatted_lines[-1])
100 finally:
101 if not socket is None:
102 socket.setdefaulttimeout(None)
103
| Home | Trees | Indices | Help |
|---|
| Generated by Epydoc 3.0.1 on Mon Oct 6 11:14:55 2014 | http://epydoc.sourceforge.net |