35 import roslib; roslib.load_manifest(
'ps3joy')
    37 from diagnostic_msgs.msg 
import DiagnosticArray, DiagnosticStatus, KeyValue
    39 from bluetooth 
import *
    47 from array 
import array
    48 import sensor_msgs.msg
    49 import rosgraph.masterapi
    51 L2CAP_PSM_HIDP_CTRL = 17
    52 L2CAP_PSM_HIDP_INTR = 19
    64         for name 
in [
"/dev/input/uinput", 
"/dev/misc/uinput", 
"/dev/uinput"]:
    66                 return os.open(name, os.O_WRONLY)
    73     def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat):
    76             print >> sys.stderr, 
"Trying to modprobe uinput."    77             os.system(
"modprobe uinput > /dev/null 2>&1")
    81                 print >> sys.stderr, 
"Can't open uinput device. Is it accessible by this user? Did you mean to run as root?"    92         UI_SET_EVBIT   = 0x40045564
    93         UI_SET_KEYBIT  = 0x40045565
    94         UI_SET_RELBIT  = 0x40045566
    95         UI_DEV_CREATE  = 0x5501
    96         UI_SET_RELBIT  = 0x40045566
    97         UI_SET_ABSBIT  = 0x40045567
    98         uinput_user_dev = 
"80sHHHHi" + (uinput.ABS_MAX+1)*4*
'i'   100         if len(axes) != len(axmin) 
or len(axes) != len(axmax):
   101             raise Exception(
"uinputjoy.__init__: axes, axmin and axmax should have same length")
   102         absmin = [0] * (uinput.ABS_MAX+1)
   103         absmax = [0] * (uinput.ABS_MAX+1)
   104         absfuzz = [2] * (uinput.ABS_MAX+1)
   105         absflat = [4] * (uinput.ABS_MAX+1)
   106         for i 
in range(0, len(axes)):
   107             absmin[axes[i]] = axmin[i]
   108             absmax[axes[i]] = axmax[i]
   109             absfuzz[axes[i]] = axfuzz[i]
   110             absflat[axes[i]] = axflat[i]
   112         os.write(self.
file, struct.pack(uinput_user_dev, 
"Sony Playstation SixAxis/DS3",
   113             uinput.BUS_USB, 0x054C, 0x0268, 0, 0, *(absmax + absmin + absfuzz + absflat)))
   115         fcntl.ioctl(self.
file, UI_SET_EVBIT, uinput.EV_KEY)
   118             fcntl.ioctl(self.
file, UI_SET_KEYBIT, b)
   121             fcntl.ioctl(self.
file, UI_SET_EVBIT, uinput.EV_ABS)
   122             fcntl.ioctl(self.
file, UI_SET_ABSBIT, a)
   124         fcntl.ioctl(self.
file, UI_DEV_CREATE)
   126         self.
value = [
None] * (len(buttons) + len(axes))
   127         self.
type = [uinput.EV_KEY] * len(buttons) + [uinput.EV_ABS] * len(axes)
   131         input_event = 
"LLHHi"   134         tl = int((t - th) * 1000000)
   135         if len(value) != len(self.
value):
   136             print >> sys.stderr, 
"Unexpected length for value in update (%i instead of %i). This is a bug."%(len(value), len(self.
value))
   137         for i 
in range(0, len(value)):
   138             if value[i] != self.
value[i]:
   139                 os.write(self.
file, struct.pack(input_event, th, tl, self.
type[i], self.
code[i], value[i]))
   140         self.
value = list(value)
   144         Exception.__init__(self, 
"Unsupported joystick.")
   147     def __init__(self, deamon, inactivity_timeout = float(1e3000)):
   159         buttons = range(0x100,0x111)
   165         for i 
in range(-4,0): 
   169         for i 
in range(4,len(axmin)-4): 
   172         self.
axmid = [sum(pair)/2 
for pair 
in zip(axmin, axmax)]
   184             rospy.init_node(
'ps3joy', anonymous=
True, disable_signals=
True)
   186             print "rosnode init failed"   187         rospy.Subscriber(
"joy/set_feedback",sensor_msgs.msg.JoyFeedbackArray,self.
set_feedback)
   229         if len(rawdata) == 50:
   230             joy_coding = 
"!1B2x3B1x4B4x12B3x1B1B1B9x4H"   231             all_data = list(struct.unpack(joy_coding, rawdata)) 
   232             state_data = all_data[20:23]
   233             data = all_data[0:20]+all_data[23:]
   235             self.diagnostics.publish(state_data)
   237                 print >> sys.stderr, 
"Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?"%prefix
   241                 curbyte = data.pop(0)
   243                     out.append(int((curbyte & (1 << k)) != 0))
   246             axis_motion = [abs(out[17:][i] - self.
axmid[i]) > 20 
for i 
in range(0,len(out)-17-4)]
   248             if any(out[0:17]) 
or any(axis_motion):
   251         elif len(rawdata) == 13:
   253             print >> sys.stderr, 
"Your bluetooth adapter is not supported. Does it support Bluetooth 2.0? Please report its model to blaise@willowgarage.com"   256             print >> sys.stderr, 
"Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?"%len(rawdata)
   260         self.joy.update([0] * 17 + self.
axmid)
   264         for feedback 
in msg.array:
   265             if feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_LED 
and feedback.id < 4:
   266                 self.
led_values[feedback.id] = int(round(feedback.intensity))
   267             elif feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_RUMBLE 
and feedback.id < 2:
   268                 self.
rumble_cmd[feedback.id] = int(feedback.intensity*255)                
   270                 rospy.logwarn(
"Feedback %s of type %s does not exist for this joystick.",feedback.id, feedback.type)
   278                    0x00, 0x00, 0x00, 0x00, self.
led_cmd,
   279                    0xff, 0x27, 0x10, 0x00, 0x32,        
   280                    0xff, 0x27, 0x10, 0x00, 0x32,        
   281                    0xff, 0x27, 0x10, 0x00, 0x32,        
   282                    0xff, 0x27, 0x10, 0x00, 0x32,        
   283                    0x00, 0x00, 0x00, 0x00, 0x00
   285         ctrl.send(array(
'B', command).tostring())
   288     def run(self, intr, ctrl):
   292             lastactivitytime = lastvalidtime = time.time()
   293             while not rospy.is_shutdown():
   294                 (rd, wr, err) = select.select([intr], [], [], 0.1)
   295                 curtime = time.time()
   296                 if len(rd) + len(wr) + len(err) == 0: 
   298                     ctrl.send(
"\x53\xf4\x42\x03\x00\x00") 
   306                         print "Connection activated"   311                         rawdata = intr.recv(128)
   312                     except BluetoothError, s:
   313                         print "Got Bluetooth error %s. Disconnecting."%s
   315                     if len(rawdata) == 0: 
   316                         print "Joystick shut down the connection, battery may be discharged."   318                     if not rosgraph.masterapi.is_online():
   319                         print "The roscore or node shutdown, ps3joy shutting down."   337                     stepout = self.
step(rawdata)
   339                         lastvalidtime = curtime
   341                         lastactivitytime = curtime
   343                     print "Joystick inactive for %.0f seconds. Disconnecting to save battery."%self.
inactivity_timeout   345                 if curtime - lastvalidtime >= 0.1: 
   347                 if curtime - lastvalidtime >= 5: 
   348                     print "No valid data for 5 seconds. Disconnecting. This should not happen, please report it."   362                                 22:
"Bluetooth Connection"}
   371         self.
diag_pub = rospy.Publisher(
'/diagnostics', DiagnosticArray)
   375         STATE_INDEX_CHARGING = 0
   376         STATE_INDEX_BATTERY = 1
   377         STATE_INDEX_CONNECTION = 2
   380         curr_time = rospy.get_rostime()
   386         diag = DiagnosticArray()
   387         diag.header.stamp = curr_time
   389         stat = DiagnosticStatus(name=
"Battery", level=DiagnosticStatus.OK, message=
"OK")
   391             battery_state_code = state[STATE_INDEX_BATTERY]
   393             if battery_state_code < 3:
   394                 stat.level = DiagnosticStatus.WARN
   395                 if battery_state_code < 1:
   396                     stat.level = DiagnosticStatus.ERROR
   397                 stat.message = 
"Please Recharge Battery (%s)." % self.
STATE_TEXTS_BATTERY[battery_state_code]
   398         except KeyError 
as ex:
   399             stat.message = 
"Invalid Battery State %s"%ex
   400             rospy.logwarn(
"Invalid Battery State %s"%ex)
   401             stat.level = DiagnosticStatus.ERROR
   402         diag.status.append(stat)
   404         stat = DiagnosticStatus(name=
'ps3joy'": Connection Type", level=DiagnosticStatus.OK, message=
"OK")
   407         except KeyError 
as ex:
   408             stat.message = 
"Invalid Connection State %s"%ex
   409             rospy.logwarn(
"Invalid Connection State %s"%ex)
   410             stat.level = DiagnosticStatus.ERROR
   411         diag.status.append(stat)
   413         stat = DiagnosticStatus(name=
'ps3joy'": Charging State", level=DiagnosticStatus.OK, message=
"OK")
   416         except KeyError 
as ex:
   417             stat.message = 
"Invalid Charging State %s"%ex
   418             rospy.logwarn(
"Invalid Charging State %s"%ex)
   419             stat.level = DiagnosticStatus.ERROR
   420         diag.status.append(stat)
   422         self.diag_pub.publish(diag)
   426         Exception.__init__(self)
   431     proc = subprocess.Popen([
'hciconfig'], stdout=subprocess.PIPE, stderr=subprocess.PIPE)
   432     (out, err) = proc.communicate()
   433     if out.find(
'UP') == -1:
   434         os.system(
"hciconfig hci0 up > /dev/null 2>&1")
   435     if out.find(
'PSCAN') == -1:
   436         os.system(
"hciconfig hci0 pscan > /dev/null 2>&1")
   443         sock = BluetoothSocket(L2CAP)
   447         sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
   454                 sock.bind((
"", port))
   458                     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."   468         self.
listen(intr_sock, ctrl_sock)
   473         self.
listen(intr_sock, ctrl_sock)
   477         while not rospy.is_shutdown():
   478             print "Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button."   480                 intr_sock.settimeout(5)
   481                 ctrl_sock.settimeout(1)
   484                         (intr, (idev, iport)) = intr_sock.accept();
   487                         if str(e) == 
'timed out':
   494                         (ctrl, (cdev, cport)) = ctrl_sock.accept();
   496                         print >> sys.stderr, 
"Got interrupt connection without control connection. Giving up on it."   500                             self.decoder.run(intr, ctrl)
   501                             print "Connection terminated."   504                             print >> sys.stderr, 
"Simultaneous connection from two different devices. Ignoring both."   509             except BadJoystickException:
   511             except KeyboardInterrupt:
   512                 print "\nCTRL+C detected. Exiting."   513                 rospy.signal_shutdown(
"\nCTRL+C detected. Exiting.")
   516                 traceback.print_exc()
   517                 print >> sys.stderr, 
"Caught exception: %s"%str(e)
   520 inactivity_timout_string = 
"--inactivity-timeout"   521 no_disable_bluetoothd_string = 
"--no-disable-bluetoothd"   522 redirect_output_string = 
"--redirect-output"   527     print "usage: ps3joy.py ["+inactivity_timout_string+
"=<n>] ["+no_disable_bluetoothd_string+
"] ["+redirect_output_string+
"]=<f>"   528     print "<n>: inactivity timeout in seconds (saves battery life)."   529     print "<f>: file name to redirect output to."   531     print "Unless "+no_disable_bluetoothd_string+
" is specified, bluetoothd will be stopped."   535     if not arg.startswith(prefix):
   537     if not arg.startswith(prefix+
"="):
   538         print "Expected '=' after "+prefix
   543 if __name__ == 
"__main__":
   546         inactivity_timeout = float(1e3000)
   547         disable_bluetoothd = 
True   549         for arg 
in sys.argv[1:]: 
   553                 str_value = arg[len(inactivity_timout_string)+1:]
   555                     inactivity_timeout = float(str_value)
   556                     if inactivity_timeout < 0:
   557                         print "Inactivity timeout must be positive."   561                     print "Error parsing inactivity timeout: "+str_value
   564             elif arg == no_disable_bluetoothd_string:
   565                 disable_bluetoothd = 
False   567                 str_value = arg[len(redirect_output_string)+1:]
   569                     print "Redirecting output to:", str_value
   570                     sys.stdout = open(str_value, 
"a", 1)
   572                     print "Error opening file to redirect output:", str_value
   574                 sys.stderr = sys.stdout
   578                 print "Ignoring parameter: '%s'"%arg
   582             print >> sys.stderr, 
"ps3joy.py must be run as root."   584         if disable_bluetoothd:
   585             os.system(
"/etc/init.d/bluetooth stop > /dev/null 2>&1")
   588             while os.system(
"hciconfig hci0 > /dev/null 2>&1") != 0:
   589                 print >> sys.stderr,  
"No bluetooth dongle found or bluez rosdep not installed. Will retry in 5 seconds."   591             if inactivity_timeout == float(1e3000):
   592                 print "No inactivity timeout was set. (Run with --help for details.)"   594                 print "Inactivity timeout set to %.0f seconds."%inactivity_timeout
   596             cm.listen_bluetooth()
   598             if disable_bluetoothd:
   599                 os.system(
"/etc/init.d/bluetooth start > /dev/null 2>&1")
   601         errorcode = e.errorcode
   602     except KeyboardInterrupt:
   603         print "\nCTRL+C detected. Exiting."   604         rospy.signal_shutdown(
"\nCTRL+C detected. Exiting.")
 
def __init__(self, deamon, inactivity_timeout=float(1e3000))
def listen_net(self, intr_port, ctrl_port)
def __init__(self, decoder)
def listen_bluetooth(self)
def listen(self, intr_sock, ctrl_sock)
def is_arg_with_param(arg, prefix)
def run(self, intr, ctrl)
def prepare_net_socket(self, port)
def set_feedback(self, msg)
def prepare_bluetooth_socket(self, port)
last_diagnostics_time
timed gate: limit to 1 Hz 
def prepare_socket(self, sock, port)
def __init__(self, errorcode)