$search
00001 #!/usr/bin/env python 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.joints 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: # remove _joint for display name 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 # Move Base 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 # Move Servos 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 = getJointsFromURDF() 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 joints = rospy.get_param('/arbotix/joints', dict()) 00099 # create sliders and publishers 00100 for name in sorted(joints.keys()): 00101 # pull angles 00102 min_angle, max_angle = getJointLimits(name, joint_defaults) 00103 # create publisher 00104 self.publishers.append(rospy.Publisher(name+'/command', Float64)) 00105 if rospy.get_param('/arbotix/joints/'+name+'/type','dynamixel') == 'dynamixel': 00106 self.relaxers.append(rospy.ServiceProxy(name+'/relax', Relax)) 00107 else: 00108 self.relaxers.append(None) 00109 # create slider 00110 s = servoSlider(self, min_angle, max_angle, name, i) 00111 servoSizer.Add(s.enabled,(i,0), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL) 00112 servoSizer.Add(s.position,(i,1), wx.GBSpan(1,1),wx.ALIGN_CENTER_VERTICAL) 00113 self.servos.append(s) 00114 i += 1 00115 00116 # add everything 00117 servoBox.Add(servoSizer) 00118 sizer.Add(servoBox, (0,1), wx.GBSpan(1,1), wx.EXPAND|wx.TOP|wx.BOTTOM|wx.RIGHT,5) 00119 self.Bind(wx.EVT_CHECKBOX, self.enableSliders) 00120 # now we can subscribe 00121 rospy.Subscriber('joint_states', JointState, self.stateCb) 00122 00123 # timer for output 00124 self.timer = wx.Timer(self, self.TIMER_ID) 00125 self.timer.Start(50) 00126 wx.EVT_CLOSE(self, self.onClose) 00127 wx.EVT_TIMER(self, self.TIMER_ID, self.onTimer) 00128 00129 # bind the panel to the paint event 00130 wx.EVT_PAINT(self, self.onPaint) 00131 self.dirty = 1 00132 self.onPaint() 00133 00134 self.SetSizerAndFit(sizer) 00135 self.Show(True) 00136 00137 def onClose(self, event): 00138 self.timer.Stop() 00139 self.Destroy() 00140 00141 def enableSliders(self, event): 00142 servo = event.GetId() 00143 if event.IsChecked(): 00144 self.servos[servo].position.Enable() 00145 else: 00146 self.servos[servo].position.Disable() 00147 if self.relaxers[servo]: 00148 self.relaxers[servo]() 00149 00150 def stateCb(self, msg): 00151 for servo in self.servos: 00152 if not servo.enabled.IsChecked(): 00153 try: 00154 idx = msg.name.index(servo.name) 00155 servo.setPosition(msg.position[idx]) 00156 except: 00157 pass 00158 00159 def onPaint(self, event=None): 00160 # this is the wx drawing surface/canvas 00161 dc = wx.PaintDC(self.movebase) 00162 dc.Clear() 00163 # draw crosshairs 00164 dc.SetPen(wx.Pen("black",1)) 00165 dc.DrawLine(width/2, 0, width/2, width) 00166 dc.DrawLine(0, width/2, width, width/2) 00167 dc.SetPen(wx.Pen("red",2)) 00168 dc.SetBrush(wx.Brush('red', wx.SOLID)) 00169 dc.SetPen(wx.Pen("black",2)) 00170 dc.DrawCircle((width/2) + self.X*(width/2), (width/2) - self.Y*(width/2), 5) 00171 00172 def onMove(self, event=None): 00173 if event.LeftIsDown(): 00174 pt = event.GetPosition() 00175 if pt[0] > 0 and pt[0] < width and pt[1] > 0 and pt[1] < width: 00176 self.forward = ((width/2)-pt[1])/2 00177 self.turn = (pt[0]-(width/2))/2 00178 self.X = (pt[0]-(width/2.0))/(width/2.0) 00179 self.Y = ((width/2.0)-pt[1])/(width/2.0) 00180 else: 00181 self.forward = 0; self.Y = 0 00182 self.turn = 0; self.X = 0 00183 self.onPaint() 00184 00185 def onTimer(self, event=None): 00186 # send joint updates 00187 for s,p in zip(self.servos,self.publishers): 00188 if s.enabled.IsChecked(): 00189 d = Float64() 00190 d.data = s.getPosition() 00191 p.publish(d) 00192 # send base updates 00193 t = Twist() 00194 t.linear.x = self.forward/150.0; t.linear.y = 0; t.linear.z = 0 00195 if self.forward > 0: 00196 t.angular.x = 0; t.angular.y = 0; t.angular.z = -self.turn/50.0 00197 else: 00198 t.angular.x = 0; t.angular.y = 0; t.angular.z = self.turn/50.0 00199 self.cmd_vel.publish(t) 00200 00201 if __name__ == '__main__': 00202 # initialize GUI 00203 rospy.init_node('controllerGUI') 00204 app = wx.PySimpleApp() 00205 frame = controllerGUI(None, True) 00206 app.MainLoop() 00207