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
00030 import roslib; roslib.load_manifest('arbotix_python')
00031 import rospy
00032 import wx
00033
00034 from math import radians
00035
00036 from geometry_msgs.msg import Twist
00037 from sensor_msgs.msg import JointState
00038 from std_msgs.msg import Float64
00039 from arbotix_msgs.srv import Relax
00040 from arbotix_python.servos import *
00041
00042 width = 325
00043
00044 class servoSlider():
00045 def __init__(self, parent, min_angle, max_angle, name, i):
00046 self.name = name
00047 if name.find("_joint") > 0:
00048 name = name[0:-6]
00049 self.position = wx.Slider(parent, -1, 0, int(min_angle*100), int(max_angle*100), wx.DefaultPosition, (150, -1), wx.SL_HORIZONTAL)
00050 self.enabled = wx.CheckBox(parent, i, name+":")
00051 self.enabled.SetValue(False)
00052 self.position.Disable()
00053
00054 def setPosition(self, angle):
00055 self.position.SetValue(int(angle*100))
00056
00057 def getPosition(self):
00058 return self.position.GetValue()/100.0
00059
00060 class controllerGUI(wx.Frame):
00061 TIMER_ID = 100
00062
00063 def __init__(self, parent, debug = False):
00064 wx.Frame.__init__(self, parent, -1, "ArbotiX Controller GUI", style = wx.DEFAULT_FRAME_STYLE & ~ (wx.RESIZE_BORDER | wx.MAXIMIZE_BOX))
00065 sizer = wx.GridBagSizer(5,5)
00066
00067
00068 drive = wx.StaticBox(self, -1, 'Move Base')
00069 drive.SetFont(wx.Font(10, wx.DEFAULT, wx.NORMAL, wx.BOLD))
00070 driveBox = wx.StaticBoxSizer(drive,orient=wx.VERTICAL)
00071 self.movebase = wx.Panel(self,size=(width,width-20))
00072 self.movebase.SetBackgroundColour('WHITE')
00073 self.movebase.Bind(wx.EVT_MOTION, self.onMove)
00074 wx.StaticLine(self.movebase, -1, (width/2, 0), (1,width), style=wx.LI_VERTICAL)
00075 wx.StaticLine(self.movebase, -1, (0, width/2), (width,1))
00076 driveBox.Add(self.movebase)
00077 sizer.Add(driveBox,(0,0),wx.GBSpan(1,1),wx.EXPAND|wx.TOP|wx.BOTTOM|wx.LEFT,5)
00078 self.forward = 0
00079 self.turn = 0
00080 self.X = 0
00081 self.Y = 0
00082 self.cmd_vel = rospy.Publisher('cmd_vel', Twist)
00083
00084
00085 servo = wx.StaticBox(self, -1, 'Move Servos')
00086 servo.SetFont(wx.Font(10, wx.DEFAULT, wx.NORMAL, wx.BOLD))
00087 servoBox = wx.StaticBoxSizer(servo,orient=wx.VERTICAL)
00088 servoSizer = wx.GridBagSizer(5,5)
00089
00090 joint_defaults = getServosFromURDF()
00091
00092 i = 0
00093 dynamixels = rospy.get_param("/arbotix/dynamixels", dict())
00094 self.servos = list()
00095 self.publishers = list()
00096 self.relaxers = list()
00097
00098 for name in sorted(dynamixels.keys()):
00099
00100 min_angle, max_angle = getServoLimits(name, joint_defaults)
00101
00102 self.publishers.append(rospy.Publisher(name+'/command', Float64))
00103 self.relaxers.append(rospy.ServiceProxy(name+'/relax', Relax))
00104
00105 s = servoSlider(self, min_angle, max_angle, name, i)
00106 servoSizer.Add(s.enabled,(i,0), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL)
00107 servoSizer.Add(s.position,(i,1), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL)
00108 self.servos.append(s)
00109 i += 1
00110
00111 servoBox.Add(servoSizer)
00112 sizer.Add(servoBox, (0,1), wx.GBSpan(1,1), wx.EXPAND|wx.TOP|wx.BOTTOM|wx.RIGHT,5)
00113 self.Bind(wx.EVT_CHECKBOX, self.enableSliders)
00114
00115 rospy.Subscriber('joint_states', JointState, self.stateCb)
00116
00117
00118 self.timer = wx.Timer(self, self.TIMER_ID)
00119 self.timer.Start(50)
00120 wx.EVT_CLOSE(self, self.onClose)
00121 wx.EVT_TIMER(self, self.TIMER_ID, self.onTimer)
00122
00123
00124 wx.EVT_PAINT(self, self.onPaint)
00125 self.dirty = 1
00126 self.onPaint()
00127
00128 self.SetSizerAndFit(sizer)
00129 self.Show(True)
00130
00131 def onClose(self, event):
00132 self.timer.Stop()
00133 self.Destroy()
00134
00135 def enableSliders(self, event):
00136 servo = event.GetId()
00137 if event.IsChecked():
00138 self.servos[servo].position.Enable()
00139 else:
00140 self.servos[servo].position.Disable()
00141 self.relaxers[servo]()
00142
00143 def stateCb(self, msg):
00144 for servo in self.servos:
00145 if not servo.enabled.IsChecked():
00146 try:
00147 idx = msg.name.index(servo.name)
00148 servo.setPosition(msg.position[idx])
00149 except:
00150 pass
00151
00152 def onPaint(self, event=None):
00153
00154 dc = wx.PaintDC(self.movebase)
00155 dc.Clear()
00156
00157 dc.SetPen(wx.Pen("black",1))
00158 dc.DrawLine(width/2, 0, width/2, width)
00159 dc.DrawLine(0, width/2, width, width/2)
00160 dc.SetPen(wx.Pen("red",2))
00161 dc.SetBrush(wx.Brush('red', wx.SOLID))
00162 dc.SetPen(wx.Pen("black",2))
00163 dc.DrawCircle((width/2) + self.X*(width/2), (width/2) - self.Y*(width/2), 5)
00164
00165 def onMove(self, event=None):
00166 if event.LeftIsDown():
00167 pt = event.GetPosition()
00168 if pt[0] > 0 and pt[0] < width and pt[1] > 0 and pt[1] < width:
00169 self.forward = ((width/2)-pt[1])/2
00170 self.turn = (pt[0]-(width/2))/2
00171 self.X = (pt[0]-(width/2.0))/(width/2.0)
00172 self.Y = ((width/2.0)-pt[1])/(width/2.0)
00173 else:
00174 self.forward = 0; self.Y = 0
00175 self.turn = 0; self.X = 0
00176 self.onPaint()
00177
00178 def onTimer(self, event=None):
00179
00180 for s,p in zip(self.servos,self.publishers):
00181 if s.enabled.IsChecked():
00182 d = Float64()
00183 d.data = s.getPosition()
00184 p.publish(d)
00185
00186 t = Twist()
00187 t.linear.x = self.forward/150.0; t.linear.y = 0; t.linear.z = 0
00188 if self.forward > 0:
00189 t.angular.x = 0; t.angular.y = 0; t.angular.z = -self.turn/50.0
00190 else:
00191 t.angular.x = 0; t.angular.y = 0; t.angular.z = self.turn/50.0
00192 self.cmd_vel.publish(t)
00193
00194 if __name__ == '__main__':
00195
00196 rospy.init_node('controllerGUI')
00197 app = wx.PySimpleApp()
00198 frame = controllerGUI(None, True)
00199 app.MainLoop()
00200