00001
00002
00003 """
00004 A simple Controller GUI to drive robots and pose heads.
00005 Copyright (c) 2008-2011 Michael E. Ferguson. All right reserved.
00006
00007 Redistribution and use in source and binary forms, with or without
00008 modification, are permitted provided that the following conditions are met:
00009 * Redistributions of source code must retain the above copyright
00010 notice, this list of conditions and the following disclaimer.
00011 * Redistributions in binary form must reproduce the above copyright
00012 notice, this list of conditions and the following disclaimer in the
00013 documentation and/or other materials provided with the distribution.
00014 * Neither the name of Vanadium Labs LLC nor the names of its
00015 contributors may be used to endorse or promote products derived
00016 from this software without specific prior written permission.
00017
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028
00029 Modifications by Patrick Goebel for the Pi Robot Project
00030 """
00031
00032 import roslib; roslib.load_manifest('pi_head_tracking_3d_part1')
00033 import rospy
00034 import wx
00035
00036 import tf
00037 from geometry_msgs.msg import PointStamped
00038 from geometry_msgs.msg import Twist
00039 from std_msgs.msg import Float64
00040
00041 width = 300
00042 height = 200
00043
00044 class PointHeadGUI(wx.Frame):
00045 TIMER_ID = 100
00046
00047 def __init__(self, parent, debug = False):
00048 wx.Frame.__init__(self, parent, -1, "Point Head GUI", style = wx.DEFAULT_FRAME_STYLE & ~ (wx.RESIZE_BORDER | wx.MAXIMIZE_BOX))
00049
00050
00051 self.tf = tf.TransformListener()
00052
00053
00054 self.tf.waitForTransform('head_pan_link', 'head_tilt_link', rospy.Time(), rospy.Duration(5.0))
00055
00056
00057 self.frames = self.tf.getFrameStrings()
00058
00059
00060 self.target_point = PointStamped()
00061
00062
00063 self.targetPub = rospy.Publisher('/target_point', PointStamped)
00064
00065 sizer = wx.GridBagSizer(15,10)
00066
00067
00068 selectFrame = wx.StaticBox(self, -1, 'Select Frame')
00069 selectFrame.SetFont(wx.Font(10, wx.DEFAULT, wx.NORMAL, wx.BOLD))
00070 selectFrameBox = wx.StaticBoxSizer(selectFrame, orient=wx.VERTICAL)
00071 frameSizer = wx.GridBagSizer(3, 10)
00072 self.frameComboBox = wx.ComboBox(self, -1, style=wx.CB_READONLY)
00073 self.Bind(wx.EVT_COMBOBOX, self.on_combobox, self.frameComboBox)
00074 self.update_combobox()
00075 frameSizer.Add(self.frameComboBox, (0, 0))
00076 selectFrameBox.Add(frameSizer)
00077 sizer.Add(selectFrameBox,(0,0),wx.GBSpan(3,10),wx.EXPAND|wx.TOP|wx.RIGHT|wx.LEFT,5)
00078
00079
00080 selectPoint = wx.StaticBox(self, -1, 'Set Target Point')
00081 selectPoint.SetFont(wx.Font(10, wx.DEFAULT, wx.NORMAL, wx.BOLD))
00082 selectPointBox = wx.StaticBoxSizer(selectPoint, orient=wx.VERTICAL)
00083 headSizer = wx.GridBagSizer(3, 10)
00084 headSizer.Add(wx.StaticText(self, -1, "x:"),(0,0), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL)
00085 self.target_point_x = wx.TextCtrl(self,-1,value=u"0.0")
00086 headSizer.Add(self.target_point_x, (0,1))
00087 headSizer.Add(wx.StaticText(self, -1, "y:"),(1,0), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL)
00088 self.target_point_y = wx.TextCtrl(self,-1,value=u"0.0")
00089 headSizer.Add(self.target_point_y, (1,1))
00090 headSizer.Add(wx.StaticText(self, -1, "z:"),(2,0), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL)
00091 self.target_point_z = wx.TextCtrl(self,-1,value=u"0.0")
00092 headSizer.Add(self.target_point_z, (2,1))
00093 selectPointBox.Add(headSizer)
00094 sizer.Add(selectPointBox, (3,0), wx.GBSpan(3,10), wx.EXPAND|wx.BOTTOM|wx.RIGHT|wx.LEFT,5)
00095
00096
00097 pointSizer = wx.GridBagSizer(1, 10)
00098 self.pointButton = wx.Button(self, -1, label="Point Head!")
00099 self.Bind(wx.EVT_BUTTON, self.on_point_button, self.pointButton)
00100 pointSizer.Add(self.pointButton, (0, 1))
00101
00102
00103 self.resetButton = wx.Button(self, -1, label="Reset Position")
00104 self.Bind(wx.EVT_BUTTON, self.on_reset_button, self.resetButton)
00105 pointSizer.Add(self.resetButton, (0, 2))
00106 sizer.Add(pointSizer, (6,0), wx.GBSpan(2,10), wx.EXPAND|wx.BOTTOM|wx.RIGHT|wx.LEFT,5)
00107
00108
00109 self.timer = wx.Timer(self, self.TIMER_ID)
00110 self.timer.Start(50)
00111 wx.EVT_CLOSE(self, self.onClose)
00112 wx.EVT_TIMER(self, self.TIMER_ID, self.onTimer)
00113
00114
00115 wx.EVT_PAINT(self, self.onPaint)
00116 self.dirty = 1
00117 self.onPaint()
00118
00119 self.SetSizerAndFit(sizer)
00120 self.Show(True)
00121
00122 def update_combobox(self):
00123 self.frameComboBox.SetItems(self.frames)
00124 selected_frame = self.get_selected_frame()
00125
00126 def get_selected_frame(self):
00127 return str(self.frameComboBox.GetValue())
00128
00129 def on_combobox(self, event):
00130 self.target_point.header.frame_id = self.get_selected_frame().rstrip()
00131
00132 def on_point_button(self, event):
00133 try:
00134 self.target_point.header.frame_id = self.get_selected_frame()
00135 self.target_point.point.x = float(self.target_point_x.GetValue().rstrip())
00136 self.target_point.point.y = float(self.target_point_y.GetValue().rstrip())
00137 self.target_point.point.z = float(self.target_point_z.GetValue().rstrip())
00138 rospy.loginfo("Publishing target point:\n" + str(self.target_point))
00139 self.targetPub.publish(self.target_point)
00140 except:
00141 rospy.loginfo("Invalid floating point coordinates. Please try again.")
00142
00143 def on_reset_button(self, event):
00144
00145 try:
00146 self.target_point.point.x = 1000.
00147 self.target_point.point.y = 0.0
00148 self.target_point.point.z = 0.0
00149 self.target_point.header.frame_id = '/base_link'
00150 rospy.loginfo("Publishing target point:\n" + str(self.target_point))
00151 self.targetPub.publish(self.target_point)
00152 except:
00153 rospy.loginfo("Invalid floating point coordinates. Please try again.")
00154
00155 def onClose(self, event):
00156 self.timer.Stop()
00157 self.Destroy()
00158
00159 def onPaint(self, event=None):
00160 pass
00161
00162 def onTimer(self, event):
00163 if rospy.is_shutdown():
00164 self.Close(True)
00165 self.Refresh()
00166
00167 def onExit(self, e):
00168 self.Close(True)
00169 self.Refresh()
00170
00171 def onError(self):
00172 self.Raise()
00173
00174 if __name__ == '__main__':
00175
00176 rospy.init_node('point_head_gui')
00177 app = wx.PySimpleApp()
00178 frame = PointHeadGUI(None, True)
00179 app.MainLoop()
00180