user_interface_node.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Copyright (c) 2008, Willow Garage, Inc.
00003 # All rights reserved.
00004 # 
00005 # Redistribution and use in source and binary forms, with or without
00006 # modification, are permitted provided that the following conditions are met:
00007 # 
00008 #     * Redistributions of source code must retain the above copyright
00009 #       notice, this list of conditions and the following disclaimer.
00010 #     * Redistributions in binary form must reproduce the above copyright
00011 #       notice, this list of conditions and the following disclaimer in the
00012 #       documentation and/or other materials provided with the distribution.
00013 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00014 #       contributors may be used to endorse or promote products derived from
00015 #       this software without specific prior written permission.
00016 # 
00017 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027 # POSSIBILITY OF SUCH DAMAGE.
00028 #
00029 ## @author Hai Nguyen/hai@gatech.edu
00030 from pkg import *
00031 from std_msgs.msg import String
00032 import wx, time, sys
00033 
00034 def key_to_command(key):
00035     ret = None
00036 
00037     if key == u'g':
00038         ret = 'debug'
00039 
00040     if key == u'd':
00041         ret = 'display'
00042 
00043     if key == u'v':
00044         ret = 'verbose'
00045 
00046     if key == u' ':
00047         ret = 'rebuild'
00048 
00049     if key == u'p':
00050         ret = 'positive'
00051 
00052     if key == u'c':
00053         ret = 'clear'
00054 
00055     return ret
00056 
00057 class KeyHandler(wx.Window):
00058     def __init__(self, parent):
00059         wx.Window.__init__(self, parent, -1, style=wx.WANTS_CHARS, name="sink")
00060         self.Bind(wx.EVT_KEY_DOWN, self.on_key_down)
00061 
00062         self.Bind(wx.EVT_LEFT_DOWN, self.on_left_down)
00063         self.Bind(wx.EVT_LEFT_UP, self.on_left_up)
00064         self.Bind(wx.EVT_LEFT_DCLICK, self.on_left_double_click)
00065 
00066         self.Bind(wx.EVT_RIGHT_DOWN, self.on_right_down)
00067         self.Bind(wx.EVT_RIGHT_UP, self.on_right_up)
00068         self.Bind(wx.EVT_RIGHT_DCLICK, self.on_right_double_click)
00069 
00070         self.Bind(wx.EVT_PAINT, self.on_paint)
00071         self.Bind(wx.EVT_SET_FOCUS, self.on_set_focus)
00072         self.Bind(wx.EVT_KILL_FOCUS, self.on_kill_focus)
00073         self.Bind(wx.EVT_SIZE, self.on_size)
00074         self.Bind(wx.EVT_UPDATE_UI, self.on_size)
00075         wx.UpdateUIEvent.SetUpdateInterval(500)
00076 
00077         self.mouse_click_pub = rospy.Publisher(MOUSE_CLICK_TOPIC, String).publish
00078         self.mouse_r_click_pub = rospy.Publisher(MOUSE_R_CLICK_TOPIC, String).publish
00079         self.laser_mode_pub  = rospy.Publisher(LASER_MODE_TOPIC, String).publish
00080         self.mouse_double_click_pub = rospy.Publisher(MOUSE_DOUBLE_CLICK_TOPIC, String).publish
00081         self.mouse_r_double_click_pub = rospy.Publisher(MOUSE_R_DOUBLE_CLICK_TOPIC, String).publish
00082         rospy.init_node('user_interface_node')
00083         self.SetBackgroundColour(wx.BLACK)
00084         self.focus = False
00085         self.text = ''
00086         self.time = time.time()
00087         self.interval = 1.0
00088 
00089     def set_text(self, text):
00090         self.text = text
00091         self.time = time.time()
00092 
00093     def on_size(self, evt):
00094         self.Refresh()
00095 
00096     def on_set_focus(self, evt):
00097         self.focus = True
00098         self.Refresh()
00099 
00100     def on_kill_focus(self, evt):
00101         self.focus = False
00102         self.Refresh()
00103 
00104     def on_left_double_click(self, evt):
00105         self.mouse_double_click_pub('True')
00106         self.set_text('DOUBLE CLICKED')
00107 
00108     def on_left_down(self, evt):
00109         self.mouse_click_pub('True')
00110         self.set_text('cli....')
00111         self.Refresh()
00112 
00113     def on_left_up(self, evt):
00114         self.mouse_click_pub('False')
00115         self.set_text('...cked')
00116         self.Refresh()
00117 
00118     def on_right_double_click(self, evt):
00119         self.mouse_r_double_click_pub('True')
00120         self.set_text('R DOUBLE CLICKED')
00121 
00122     def on_right_down(self, evt):
00123         self.mouse_r_click_pub('True')
00124         self.set_text('right cli....')
00125         self.Refresh()
00126 
00127     def on_right_up(self, evt):
00128         self.mouse_r_click_pub('False')
00129         self.set_text('...cked')
00130         self.Refresh()
00131 
00132     def on_key_down(self, evt):
00133         c = unichr(evt.GetRawKeyCode())
00134         command = key_to_command(c)
00135         if command is not None:
00136             #print 'publishing', command
00137             self.laser_mode_pub(command)
00138             self.set_text(command)
00139         else:
00140             self.set_text(unichr(evt.GetRawKeyCode()))
00141         self.Refresh()
00142 
00143     def on_paint(self, evt):
00144         dc   = wx.PaintDC(self)
00145         font = dc.GetFont()
00146         font.SetPointSize(20)
00147         dc.SetFont(font)
00148         rect = self.GetClientRect()
00149 
00150         if self.focus:
00151             dc.SetTextForeground(wx.GREEN)
00152             dc.DrawLabel("Focused.", rect, wx.ALIGN_CENTER)
00153         else:
00154             dc.SetTextForeground(wx.RED)
00155             dc.DrawLabel("Got no focus.", rect, wx.ALIGN_CENTER)
00156 
00157         dc.SetTextForeground(wx.WHITE)
00158         dc.DrawLabel('g - debug\nd - display\nv - verbose\np - positive\nc - clear\nspace - rebuild', rect, wx.ALIGN_LEFT | wx.ALIGN_TOP)
00159 
00160         if (time.time() - self.time) < self.interval:
00161             dc.SetFont(wx.Font(20, wx.MODERN, wx.NORMAL, wx.NORMAL))
00162             dc.SetTextForeground(wx.WHITE)
00163             dc.DrawLabel(self.text, rect, wx.ALIGN_BOTTOM | wx.ALIGN_CENTER)
00164 
00165 app   = wx.PySimpleApp()
00166 frame = wx.Frame(None, wx.ID_ANY, name='Clickable World GUI', size=(800,600))
00167 win   = KeyHandler(frame) 
00168 frame.Show(True)
00169 win.SetFocus()
00170 #rospy.ready(sys.argv[0])
00171 app.MainLoop()
00172 
00173 


laser_interface
Author(s): Hai Nguyen and Travis Deyle. Advisor: Prof. Charlie Kemp, Lab: Healthcare Robotics Lab at Georgia Tech
autogenerated on Wed Nov 27 2013 11:45:51