$search
00001 #!/usr/bin/python 00002 #*********************************************************** 00003 #* Software License Agreement (BSD License) 00004 #* 00005 #* Copyright (c) 2009, Willow Garage, Inc. 00006 #* All rights reserved. 00007 #* 00008 #* Redistribution and use in source and binary forms, with or without 00009 #* modification, are permitted provided that the following conditions 00010 #* are met: 00011 #* 00012 #* * Redistributions of source code must retain the above copyright 00013 #* notice, this list of conditions and the following disclaimer. 00014 #* * Redistributions in binary form must reproduce the above 00015 #* copyright notice, this list of conditions and the following 00016 #* disclaimer in the documentation and/or other materials provided 00017 #* with the distribution. 00018 #* * Neither the name of the Willow Garage nor the names of its 00019 #* contributors may be used to endorse or promote products derived 00020 #* from this software without specific prior written permission. 00021 #* 00022 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 #* POSSIBILITY OF SUCH DAMAGE. 00034 #*********************************************************** 00035 00036 from bluetooth import * 00037 import select 00038 import fcntl 00039 import os 00040 import time 00041 import sys 00042 import traceback 00043 import subprocess 00044 00045 L2CAP_PSM_HIDP_CTRL = 17 00046 L2CAP_PSM_HIDP_INTR = 19 00047 00048 class uinput: 00049 EV_KEY = 1 00050 EV_REL = 2 00051 EV_ABS = 3 00052 BUS_USB = 3 00053 ABS_MAX = 0x3f 00054 00055 class uinputjoy: 00056 def open_uinput(self): 00057 for name in ["/dev/input/uinput", "/dev/misc/uinput", "/dev/uinput"]: 00058 try: 00059 return os.open(name, os.O_WRONLY) 00060 break 00061 except Exception, e: 00062 #print >> sys.stderr, "Error opening uinput: %s"%str(e) 00063 pass 00064 return None 00065 00066 def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat): 00067 self.file = self.open_uinput() 00068 if self.file == None: 00069 print >> sys.stderr, "Trying to modprobe uinput." 00070 os.system("modprobe uinput > /dev/null 2>&1") 00071 time.sleep(1) # uinput isn't ready to go right away. 00072 self.file = self.open_uinput() 00073 if self.file == None: 00074 print >> sys.stderr, "Can't open uinput device. Is it accessible by this user? Did you mean to run as root?" 00075 raise IOError 00076 #id = uinput.input_id() 00077 #id.bustype = uinput.BUS_USB 00078 #id.vendor = 0x054C 00079 #id.product = 0x0268 00080 #id.version = 0 00081 #info = uinput.uinput_user_dev() 00082 #info.name = "Sony Playstation SixAxis/DS3" 00083 #info.id = id 00084 00085 UI_SET_EVBIT = 0x40045564 00086 UI_SET_KEYBIT = 0x40045565 00087 UI_SET_RELBIT = 0x40045566 00088 UI_DEV_CREATE = 0x5501 00089 UI_SET_RELBIT = 0x40045566 00090 UI_SET_ABSBIT = 0x40045567 00091 uinput_user_dev = "80sHHHHi" + (uinput.ABS_MAX+1)*4*'i' 00092 00093 if len(axes) != len(axmin) or len(axes) != len(axmax): 00094 raise Exception("uinputjoy.__init__: axes, axmin and axmax should have same length") 00095 absmin = [0] * (uinput.ABS_MAX+1) 00096 absmax = [0] * (uinput.ABS_MAX+1) 00097 absfuzz = [2] * (uinput.ABS_MAX+1) 00098 absflat = [4] * (uinput.ABS_MAX+1) 00099 for i in range(0, len(axes)): 00100 absmin[axes[i]] = axmin[i] 00101 absmax[axes[i]] = axmax[i] 00102 absfuzz[axes[i]] = axfuzz[i] 00103 absflat[axes[i]] = axflat[i] 00104 00105 os.write(self.file, struct.pack(uinput_user_dev, "Sony Playstation SixAxis/DS3", 00106 uinput.BUS_USB, 0x054C, 0x0268, 0, 0, *(absmax + absmin + absfuzz + absflat))) 00107 00108 fcntl.ioctl(self.file, UI_SET_EVBIT, uinput.EV_KEY) 00109 00110 for b in buttons: 00111 fcntl.ioctl(self.file, UI_SET_KEYBIT, b) 00112 00113 for a in axes: 00114 fcntl.ioctl(self.file, UI_SET_EVBIT, uinput.EV_ABS) 00115 fcntl.ioctl(self.file, UI_SET_ABSBIT, a) 00116 00117 fcntl.ioctl(self.file, UI_DEV_CREATE) 00118 00119 self.value = [None] * (len(buttons) + len(axes)) 00120 self.type = [uinput.EV_KEY] * len(buttons) + [uinput.EV_ABS] * len(axes) 00121 self.code = buttons + axes 00122 00123 def update(self, value): 00124 input_event = "LLHHi" 00125 t = time.time() 00126 th = int(t) 00127 tl = int((t - th) * 1000000) 00128 if len(value) != len(self.value): 00129 print >> sys.stderr, "Unexpected length for value in update (%i instead of %i). This is a bug."%(len(value), len(self.value)) 00130 for i in range(0, len(value)): 00131 if value[i] != self.value[i]: 00132 os.write(self.file, struct.pack(input_event, th, tl, self.type[i], self.code[i], value[i])) 00133 self.value = list(value) 00134 00135 class BadJoystickException(Exception): 00136 def __init__(self): 00137 Exception.__init__(self, "Unsupported joystick.") 00138 00139 class decoder: 00140 def __init__(self, inactivity_timeout = float(1e3000)): 00141 #buttons=[uinput.BTN_SELECT, uinput.BTN_THUMBL, uinput.BTN_THUMBR, uinput.BTN_START, 00142 # uinput.BTN_FORWARD, uinput.BTN_RIGHT, uinput.BTN_BACK, uinput.BTN_LEFT, 00143 # uinput.BTN_TL, uinput.BTN_TR, uinput.BTN_TL2, uinput.BTN_TR2, 00144 # uinput.BTN_X, uinput.BTN_A, uinput.BTN_B, uinput.BTN_Y, 00145 # uinput.BTN_MODE] 00146 #axes=[uinput.ABS_X, uinput.ABS_Y, uinput.ABS_Z, uinput.ABS_RX, 00147 # uinput.ABS_RX, uinput.ABS_RY, uinput.ABS_PRESSURE, uinput.ABS_DISTANCE, 00148 # uinput.ABS_THROTTLE, uinput.ABS_RUDDER, uinput.ABS_WHEEL, uinput.ABS_GAS, 00149 # uinput.ABS_HAT0Y, uinput.ABS_HAT1Y, uinput.ABS_HAT2Y, uinput.ABS_HAT3Y, 00150 # uinput.ABS_TILT_X, uinput.ABS_TILT_Y, uinput.ABS_MISC, uinput.ABS_RZ, 00151 # ] 00152 buttons = range(0x100,0x111) 00153 axes = range(0, 20) 00154 axmin = [0] * 20 00155 axmax = [255] * 20 00156 axfuzz = [2] * 20 00157 axflat = [4] * 20 00158 for i in range(-4,0): # Gyros have more bits than other axes 00159 axmax[i] = 1023 00160 axfuzz[i] = 4 00161 axflat[i] = 4 00162 for i in range(4,len(axmin)-4): # Buttons should be zero when not pressed 00163 axmin[i] = -axmax[i] 00164 self.joy = uinputjoy(buttons, axes, axmin, axmax, axfuzz, axflat) 00165 self.axmid = [sum(pair)/2 for pair in zip(axmin, axmax)] 00166 self.fullstop() # Probably useless because of uinput startup bug 00167 self.outlen = len(buttons) + len(axes) 00168 self.inactivity_timeout = inactivity_timeout 00169 00170 step_active = 1 00171 step_idle = 2 00172 step_error = 3 00173 00174 def step(self, rawdata): # Returns true if the packet was legal 00175 if len(rawdata) == 50: 00176 joy_coding = "!1B2x3B1x4B4x12B15x4H" 00177 data = list(struct.unpack(joy_coding, rawdata)) 00178 prefix = data.pop(0) 00179 if prefix != 161: 00180 print >> sys.stderr, "Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?"%prefix 00181 return self.step_error 00182 out = [] 00183 for j in range(0,2): # Split out the buttons. 00184 curbyte = data.pop(0) 00185 for k in range(0,8): 00186 out.append(int((curbyte & (1 << k)) != 0)) 00187 out = out + data 00188 self.joy.update(out) 00189 axis_motion = [abs(out[17:][i] - self.axmid[i]) > 20 for i in range(0,len(out)-17-4)] 00190 # 17 buttons, 4 inertial sensors 00191 if any(out[0:17]) or any(axis_motion): 00192 return self.step_active 00193 return self.step_idle 00194 elif len(rawdata) == 13: 00195 #print list(rawdata) 00196 print >> sys.stderr, "Your bluetooth adapter is not supported. Does it support Bluetooth 2.0? Please report its model to blaise@willowgarage.com" 00197 raise BadJoystickException() 00198 else: 00199 print >> sys.stderr, "Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?"%len(rawdata) 00200 return self.step_error 00201 00202 def fullstop(self): 00203 self.joy.update([0] * 17 + self.axmid) 00204 00205 def run(self, intr, ctrl): 00206 activated = False 00207 try: 00208 self.fullstop() 00209 lastactivitytime = lastvalidtime = time.time() 00210 while True: 00211 (rd, wr, err) = select.select([intr], [], [], 0.1) 00212 curtime = time.time() 00213 if len(rd) + len(wr) + len(err) == 0: # Timeout 00214 #print "Activating connection." 00215 ctrl.send("\x53\xf4\x42\x03\x00\x00") # Try activating the stream. 00216 else: # Got a frame. 00217 #print "Got a frame at ", curtime, 1 / (curtime - lastvalidtime) 00218 if not activated: 00219 print "Connection activated" 00220 activated = True 00221 try: 00222 rawdata = intr.recv(128) 00223 except BluetoothError, s: 00224 print "Got Bluetooth error %s. Disconnecting."%s 00225 return 00226 if len(rawdata) == 0: # Orderly shutdown of socket 00227 print "Joystick shut down the connection, battery may be discharged." 00228 return 00229 stepout = self.step(rawdata) 00230 if stepout != self.step_error: 00231 lastvalidtime = curtime 00232 if stepout == self.step_active: 00233 lastactivitytime = curtime 00234 if curtime - lastactivitytime > self.inactivity_timeout: 00235 print "Joystick inactive for %.0f seconds. Disconnecting to save battery."%self.inactivity_timeout 00236 return 00237 if curtime - lastvalidtime >= 0.1: # Zero all outputs if we don't hear a valid frame for 0.1 to 0.2 seconds 00238 self.fullstop() 00239 if curtime - lastvalidtime >= 5: # Disconnect if we don't hear a valid frame for 5 seconds 00240 print "No valid data for 5 seconds. Disconnecting. This should not happen, please report it." 00241 return 00242 time.sleep(0.005) # No need to blaze through the loop when there is an error 00243 finally: 00244 self.fullstop() 00245 00246 class Quit(Exception): 00247 def __init__(self, errorcode): 00248 Exception.__init__(self) 00249 self.errorcode = errorcode 00250 00251 def check_hci_status(): 00252 # Check if hci0 is up and pscanning, take action as necessary. 00253 proc = subprocess.Popen(['hciconfig'], stdout=subprocess.PIPE, stderr=subprocess.PIPE) 00254 (out, err) = proc.communicate() 00255 if out.find('UP') == -1: 00256 os.system("hciconfig hci0 up > /dev/null 2>&1") 00257 if out.find('PSCAN') == -1: 00258 os.system("hciconfig hci0 pscan > /dev/null 2>&1") 00259 00260 class connection_manager: 00261 def __init__(self, decoder): 00262 self.decoder = decoder 00263 self.shutdown = False 00264 00265 def prepare_bluetooth_socket(self, port): 00266 sock = BluetoothSocket(L2CAP) 00267 return self.prepare_socket(sock, port) 00268 00269 def prepare_net_socket(self, port): 00270 sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) 00271 return self.prepare_socket(sock, port) 00272 00273 def prepare_socket(self, sock, port): 00274 first_loop = True 00275 while True: 00276 try: 00277 sock.bind(("", port)) 00278 except Exception, e: 00279 print repr(e) 00280 if first_loop: 00281 print >> sys.stderr, "Error binding to socket, will retry every 5 seconds. Do you have another ps3joy.py running? This error occurs on some distributions (such as Ubuntu Karmic). Please read http://www.ros.org/wiki/ps3joy/Troubleshooting for solutions." 00282 first_loop = False 00283 time.sleep(0.5) 00284 continue 00285 sock.listen(1) 00286 return sock 00287 00288 def listen_net(self,intr_port, ctrl_port): 00289 intr_sock = self.prepare_net_socket(intr_port) 00290 ctrl_sock = self.prepare_net_socket(ctrl_port) 00291 self.listen(intr_sock, ctrl_sock) 00292 00293 def listen_bluetooth(self): 00294 intr_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_INTR) 00295 ctrl_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_CTRL) 00296 self.listen(intr_sock, ctrl_sock) 00297 00298 def listen(self, intr_sock, ctrl_sock): 00299 self.n = 0 00300 while not self.shutdown: 00301 print "Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button." 00302 try: 00303 intr_sock.settimeout(5) 00304 ctrl_sock.settimeout(1) 00305 while True: 00306 try: 00307 (intr, (idev, iport)) = intr_sock.accept(); 00308 break 00309 except Exception, e: 00310 if str(e) == 'timed out': 00311 check_hci_status() 00312 else: 00313 raise 00314 00315 try: 00316 try: 00317 (ctrl, (cdev, cport)) = ctrl_sock.accept(); 00318 except Exception, e: 00319 print >> sys.stderr, "Got interrupt connection without control connection. Giving up on it." 00320 continue 00321 try: 00322 if idev == cdev: 00323 self.decoder.run(intr, ctrl) 00324 print "Connection terminated." 00325 else: 00326 print >> sys.stderr, "Simultaneous connection from two different devices. Ignoring both." 00327 finally: 00328 ctrl.close() 00329 finally: 00330 intr.close() 00331 except BadJoystickException: 00332 pass 00333 except KeyboardInterrupt: 00334 print "CTRL+C detected. Exiting." 00335 quit(0) 00336 except Exception, e: 00337 traceback.print_exc() 00338 print >> sys.stderr, "Caught exception: %s"%str(e) 00339 time.sleep(1) 00340 print 00341 00342 inactivity_timout_string = "--inactivity-timeout" 00343 no_disable_bluetoothd_string = "--no-disable-bluetoothd" 00344 redirect_output_string = "--redirect-output" 00345 00346 def usage(errcode): 00347 print "usage: ps3joy.py ["+inactivity_timout_string+"=<n>] ["+no_disable_bluetoothd_string+"] ["+redirect_output_string+"]=<f>" 00348 print "<n>: inactivity timeout in seconds (saves battery life)." 00349 print "<f>: file name to redirect output to." 00350 print "Unless "+no_disable_bluetoothd_string+" is specified, bluetoothd will be stopped." 00351 raise Quit(errcode) 00352 00353 def is_arg_with_param(arg, prefix): 00354 if not arg.startswith(prefix): 00355 return False 00356 if not arg.startswith(prefix+"="): 00357 print "Expected '=' after "+prefix 00358 print 00359 usage(1) 00360 return True 00361 00362 if __name__ == "__main__": 00363 errorcode = 0 00364 try: 00365 inactivity_timeout = float(1e3000) 00366 disable_bluetoothd = True 00367 for arg in sys.argv[1:]: # Be very tolerant in case we are roslaunched. 00368 if arg == "--help": 00369 usage(0) 00370 elif is_arg_with_param(arg, inactivity_timout_string): 00371 str_value = arg[len(inactivity_timout_string)+1:] 00372 try: 00373 inactivity_timeout = float(str_value) 00374 if inactivity_timeout < 0: 00375 print "Inactivity timeout must be positive." 00376 print 00377 usage(1) 00378 except ValueError: 00379 print "Error parsing inactivity timeout: "+str_value 00380 print 00381 usage(1) 00382 elif arg == no_disable_bluetoothd_string: 00383 disable_bluetoothd = False 00384 elif is_arg_with_param(arg, redirect_output_string): 00385 str_value = arg[len(redirect_output_string)+1:] 00386 try: 00387 print "Redirecting output to:", str_value 00388 sys.stdout = open(str_value, "a", 1) 00389 except IOError, e: 00390 print "Error opening file to redirect output:", str_value 00391 raise Quit(1) 00392 sys.stderr = sys.stdout 00393 else: 00394 print "Ignoring parameter: '%s'"%arg 00395 if os.getuid() != 0: 00396 print >> sys.stderr, "ps3joy.py must be run as root." 00397 quit(1) 00398 if disable_bluetoothd: 00399 os.system("/etc/init.d/bluetooth stop > /dev/null 2>&1") 00400 time.sleep(1) # Give the socket time to be available. 00401 try: 00402 while os.system("hciconfig hci0 > /dev/null 2>&1") != 0: 00403 print >> sys.stderr, "No bluetooth dongle found or bluez rosdep not installed. Will retry in 5 seconds." 00404 time.sleep(5) 00405 if inactivity_timeout == float(1e3000): 00406 print "No inactivity timeout was set. (Run with --help for details.)" 00407 else: 00408 print "Inactivity timeout set to %.0f seconds."%inactivity_timeout 00409 cm = connection_manager(decoder(inactivity_timeout = inactivity_timeout)) 00410 cm.listen_bluetooth() 00411 finally: 00412 if disable_bluetoothd: 00413 os.system("/etc/init.d/bluetooth start > /dev/null 2>&1") 00414 except Quit, e: 00415 errorcode = e.errorcode 00416 except KeyboardInterrupt: 00417 print "CTRL+C detected. Exiting." 00418 exit(errorcode) 00419