test_robot_mon.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 ##\author Kevin Watts
00036 
00037 ##\brief Tests that robot monitor opens and doesn't throw exception
00038 
00039 PKG = 'robot_monitor'
00040 import roslib; roslib.load_manifest(PKG)
00041 
00042 WXVER = '2.8'
00043 import wxversion
00044 if wxversion.checkInstalled(WXVER):
00045   wxversion.select(WXVER)
00046 else:
00047   print >> sys.stderr, "This application requires wxPython version %s"%(WXVER)
00048   sys.exit(1)
00049 
00050 from robot_monitor.robot_monitor_panel import RobotMonitorPanel
00051 import wx
00052 
00053 import threading
00054 import unittest
00055 import rospy, rostest
00056 from time import sleep
00057 import sys
00058 from optparse import OptionParser
00059 
00060 DURATION = 10
00061 
00062 ##\brief Main frame of robot monitor
00063 class RobotMonitorFrame(wx.Frame):
00064     def __init__(self, parent, title):
00065         wx.Frame.__init__(self, parent, wx.ID_ANY, title)
00066 
00067         self.panel = RobotMonitorPanel(self)
00068         
00069     def on_exit(self, e):
00070         self.Close(True)
00071 
00072 ##\brief wxApp of robot monitor
00073 class RobotMonitorApp(wx.App):
00074     def OnInit(self):
00075         self._frame = RobotMonitorFrame(None, 'Robot Monitor')
00076         self._frame.SetSize(wx.Size(500, 700))
00077         self._frame.Layout()
00078         #self._frame.Centre()
00079         self._frame.Show(True)
00080         return True
00081 
00082 class RoMonRunner(threading.Thread):
00083     def __init__(self):
00084         threading.Thread.__init__(self)
00085         self.app = RobotMonitorApp()
00086         
00087     def run(self):
00088         self.app.MainLoop()
00089         
00090 
00091 class TestRobotMonitor(unittest.TestCase):
00092     def __init__(self, *args):
00093         super(TestRobotMonitor, self).__init__(*args)
00094         
00095         rospy.init_node('test_robot_monitor', anonymous=True)
00096         parser = OptionParser(usage="usage ./%prog [options]", prog="test_robot_monitor.py")
00097 
00098         # Option comes with rostest, will fail w/o this line
00099         parser.add_option('--gtest_output', action="store",
00100                           dest="gtest")
00101 
00102         options, args = parser.parse_args(rospy.myargv())
00103 
00104         self.runner = RoMonRunner()
00105         self.runner.start()
00106         
00107     def test_robot_monitor(self):
00108         start = rospy.get_time()
00109         while not rospy.is_shutdown():
00110             if rospy.get_time() - start > DURATION:
00111                 break
00112             self.assert_(self.runner.isAlive(), "Thread running robot monitor isn't running")
00113             sleep(1.0)
00114             
00115         # Hack for closing the app
00116         try:
00117             wx.CallAfter(self.runner.app._frame.on_exit(None))
00118             self.runner.join(5)
00119         except:
00120             import traceback
00121             self.assert_(False, "Caught exception closing robot monitor: %s" % traceback.format_exc())
00122 
00123         self.assert_(not self.runner.isAlive(), "Thread running robot monitor didn't join up")
00124         self.assert_(not rospy.is_shutdown(), "Rospy shut down")
00125 
00126 
00127 if __name__ == '__main__':
00128     rostest.run(PKG, sys.argv[0], TestRobotMonitor, sys.argv)
00129     


robot_monitor
Author(s): Kevin Watts (watts@willowgarage.com), Josh Faust (jfaust@willowgarage.com)
autogenerated on Thu Apr 24 2014 15:20:23