ps3joy_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2009, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 
34 from __future__ import print_function
35 import roslib
36 import rospy
37 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
38 
39 from bluetooth import *
40 import select
41 import struct
42 import fcntl
43 import os
44 import time
45 import sys
46 import traceback
47 import subprocess
48 from array import array
49 import sensor_msgs.msg
50 import rosgraph.masterapi
51 
52 roslib.load_manifest('ps3joy')
53 
54 L2CAP_PSM_HIDP_CTRL = 17
55 L2CAP_PSM_HIDP_INTR = 19
56 inactivity_timout_string = "--inactivity-timeout"
57 no_disable_bluetoothd_string = "--no-disable-bluetoothd"
58 redirect_output_string = "--redirect-output"
59 
60 
61 class uinput:
62  EV_KEY = 1
63  EV_REL = 2
64  EV_ABS = 3
65  BUS_USB = 3
66  ABS_MAX = 0x3f
67 
68 
69 class uinputjoy:
70  def open_uinput(self):
71  for name in ["/dev/input/uinput", "/dev/misc/uinput", "/dev/uinput"]:
72  try:
73  return os.open(name, os.O_WRONLY)
74  break
75  except Exception as e:
76  pass
77  return None
78 
79  def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat):
80  self.file = self.open_uinput()
81  if self.file is None:
82  print("Trying to modprobe uinput.", file=sys.stderr)
83  os.system("modprobe uinput > /dev/null 2>&1")
84  time.sleep(1) # uinput isn't ready to go right away.
85  self.file = self.open_uinput()
86  if self.file is None:
87  print("Can't open uinput device. Is it accessible by this user? Did you mean to run as root?",
88  file=sys.stderr)
89  raise IOError
90 
91  UI_SET_EVBIT = 0x40045564
92  UI_SET_KEYBIT = 0x40045565
93  UI_SET_RELBIT = 0x40045566
94  UI_DEV_CREATE = 0x5501
95  UI_SET_RELBIT = 0x40045566
96  UI_SET_ABSBIT = 0x40045567
97  uinput_user_dev = "80sHHHHi" + (uinput.ABS_MAX + 1) * 4 * 'i'
98 
99  if len(axes) != len(axmin) or len(axes) != len(axmax):
100  raise Exception("uinputjoy.__init__: axes, axmin and axmax should have same length")
101  absmin = [0] * (uinput.ABS_MAX+1)
102  absmax = [0] * (uinput.ABS_MAX+1)
103  absfuzz = [2] * (uinput.ABS_MAX+1)
104  absflat = [4] * (uinput.ABS_MAX+1)
105  for i in range(0, len(axes)):
106  absmin[axes[i]] = axmin[i]
107  absmax[axes[i]] = axmax[i]
108  absfuzz[axes[i]] = axfuzz[i]
109  absflat[axes[i]] = axflat[i]
110 
111  os.write(self.file, struct.pack(uinput_user_dev, "Sony Playstation SixAxis/DS3",
112  uinput.BUS_USB, 0x054C, 0x0268, 0, 0, *(absmax + absmin + absfuzz + absflat)))
113 
114  fcntl.ioctl(self.file, UI_SET_EVBIT, uinput.EV_KEY)
115 
116  for b in buttons:
117  fcntl.ioctl(self.file, UI_SET_KEYBIT, b)
118 
119  for a in axes:
120  fcntl.ioctl(self.file, UI_SET_EVBIT, uinput.EV_ABS)
121  fcntl.ioctl(self.file, UI_SET_ABSBIT, a)
122 
123  fcntl.ioctl(self.file, UI_DEV_CREATE)
124 
125  self.value = [None] * (len(buttons) + len(axes))
126  self.type = [uinput.EV_KEY] * len(buttons) + [uinput.EV_ABS] * len(axes)
127  self.code = buttons + axes
128 
129  def update(self, value):
130  input_event = "LLHHi"
131  t = time.time()
132  th = int(t)
133  tl = int((t - th) * 1000000)
134  if len(value) != len(self.value):
135  print("Unexpected length for value in update (%i instead of %i). This is a bug."
136  % (len(value), len(self.value)), file=sys.stderr)
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)
141 
142 
143 class BadJoystickException(Exception):
144  def __init__(self):
145  Exception.__init__(self, "Unsupported joystick.")
146 
147 
148 class decoder:
149  def __init__(self, deamon, inactivity_timeout=float(1e3000)):
150  # buttons=[uinput.BTN_SELECT, uinput.BTN_THUMBL, uinput.BTN_THUMBR, uinput.BTN_START,
151  # uinput.BTN_FORWARD, uinput.BTN_RIGHT, uinput.BTN_BACK, uinput.BTN_LEFT,
152  # uinput.BTN_TL, uinput.BTN_TR, uinput.BTN_TL2, uinput.BTN_TR2,
153  # uinput.BTN_X, uinput.BTN_A, uinput.BTN_B, uinput.BTN_Y,
154  # uinput.BTN_MODE]
155  # axes=[uinput.ABS_X, uinput.ABS_Y, uinput.ABS_Z, uinput.ABS_RX,
156  # uinput.ABS_RX, uinput.ABS_RY, uinput.ABS_PRESSURE, uinput.ABS_DISTANCE,
157  # uinput.ABS_THROTTLE, uinput.ABS_RUDDER, uinput.ABS_WHEEL, uinput.ABS_GAS,
158  # uinput.ABS_HAT0Y, uinput.ABS_HAT1Y, uinput.ABS_HAT2Y, uinput.ABS_HAT3Y,
159  # uinput.ABS_TILT_X, uinput.ABS_TILT_Y, uinput.ABS_MISC, uinput.ABS_RZ]
160  buttons = range(0x100, 0x111)
161  axes = range(0, 20)
162  axmin = [0] * 20
163  axmax = [255] * 20
164  axfuzz = [2] * 20
165  axflat = [4] * 20
166  for i in range(-4, 0): # Gyros have more bits than other axes
167  axmax[i] = 1023
168  axfuzz[i] = 4
169  axflat[i] = 4
170  for i in range(4, len(axmin) - 4): # Buttons should be zero when not pressed
171  axmin[i] = -axmax[i]
172  self.joy = uinputjoy(buttons, axes, axmin, axmax, axfuzz, axflat)
173  self.axmid = [sum(pair) / 2 for pair in zip(axmin, axmax)]
174  self.fullstop() # Probably useless because of uinput startup bug
175  self.outlen = len(buttons) + len(axes)
176  self.inactivity_timeout = inactivity_timeout
177  self.deamon = deamon
178  self.init_ros()
179  step_active = 1
180  step_idle = 2
181  step_error = 3
182 
183  def init_ros(self):
184  rospy.init_node('ps3joy', anonymous=True, disable_signals=True)
185  rospy.Subscriber("joy/set_feedback", sensor_msgs.msg.JoyFeedbackArray, self.set_feedback)
187  self.led_values = [1, 0, 0, 0]
188  self.rumble_cmd = [0, 255]
189  self.led_cmd = 2
190  self.core_down = False
191 
192  # ********************************************************************************
193  # Raw Data Format
194  # unsigned char ReportType; //Report Type 01
195  # unsigned char Reserved1; // Unknown
196  # unsigned int ButtonState; // Main buttons
197  # unsigned char PSButtonState; // PS button
198  # unsigned char Reserved2; // Unknown
199  # unsigned char LeftStickX; // left Joystick X axis 0 - 255, 128 is mid
200  # unsigned char LeftStickY; // left Joystick Y axis 0 - 255, 128 is mid
201  # unsigned char RightStickX; // right Joystick X axis 0 - 255, 128 is mid
202  # unsigned char RightStickY; // right Joystick Y axis 0 - 255, 128 is mid
203  # unsigned char Reserved3[4]; // Unknown
204  # unsigned char PressureUp; // digital Pad Up button Pressure 0 - 255
205  # unsigned char PressureRight; // digital Pad Right button Pressure 0 - 255
206  # unsigned char PressureDown; // digital Pad Down button Pressure 0 - 255
207  # unsigned char PressureLeft; // digital Pad Left button Pressure 0 - 255
208  # unsigned char PressureL2; // digital Pad L2 button Pressure 0 - 255
209  # unsigned char PressureR2; // digital Pad R2 button Pressure 0 - 255
210  # unsigned char PressureL1; // digital Pad L1 button Pressure 0 - 255
211  # unsigned char PressureR1; // digital Pad R1 button Pressure 0 - 255
212  # unsigned char PressureTriangle; // digital Pad Triangle button Pressure 0 - 255
213  # unsigned char PressureCircle; // digital Pad Circle button Pressure 0 - 255
214  # unsigned char PressureCross; // digital Pad Cross button Pressure 0 - 255
215  # unsigned char PressureSquare; // digital Pad Square button Pressure 0 - 255
216  # unsigned char Reserved4[3]; // Unknown
217  # unsigned char Charge; // charging status ? 02 = charge, 03 = normal
218  # unsigned char Power; // Battery status
219  # unsigned char Connection; // Connection Type
220  # unsigned char Reserved5[9]; // Unknown
221  # unsigned int AccelerometerX; // X axis accelerometer Big Endian 0 - 1023
222  # unsigned int Accelero // Y axis accelerometer Big Endian 0 - 1023
223  # unsigned int AccelerometerZ; // Z axis accelerometer Big Endian 0 - 1023
224  # unsigned int GyrometerX; // Z axis Gyro Big Endian 0 - 1023
225  # *********************************************************************************
226  def step(self, rawdata): # Returns true if the packet was legal
227  if len(rawdata) == 50:
228  joy_coding = "!1B2x3B1x4B4x12B3x1B1B1B9x4H"
229  all_data = list(struct.unpack(joy_coding, rawdata)) # removing power data
230  state_data = all_data[20:23]
231  data = all_data[0:20]+all_data[23:]
232  prefix = data.pop(0)
233  self.diagnostics.publish(state_data)
234  if prefix != 161:
235  print("Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?" % prefix,
236  file=sys.stderr)
237  return self.step_error
238  out = []
239  for j in range(0, 2): # Split out the buttons.
240  curbyte = data.pop(0)
241  for k in range(0, 8):
242  out.append(int((curbyte & (1 << k)) != 0))
243  out = out + data
244  self.joy.update(out)
245  axis_motion = [
246  abs(out[17:][i] - self.axmid[i]) > 20 for i in range(0, len(out) - 17 - 4)
247  ] # 17 buttons, 4 inertial sensors
248 
249  if any(out[0:17]) or any(axis_motion):
250  return self.step_active
251  return self.step_idle
252  elif len(rawdata) == 13:
253  print("Your bluetooth adapter is not supported. Does it support Bluetooth 2.0?",
254  file=sys.stderr)
255  raise BadJoystickException()
256  else:
257  print("Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?"
258  % len(rawdata), file=sys.stderr)
259  return self.step_error
260 
261  def fullstop(self):
262  self.joy.update([0] * 17 + self.axmid)
263 
264  def set_feedback(self, msg):
265  for feedback in msg.array:
266  if feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_LED and feedback.id < 4:
267  self.led_values[feedback.id] = int(round(feedback.intensity))
268  elif feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_RUMBLE and feedback.id < 2:
269  self.rumble_cmd[feedback.id] = int(feedback.intensity*255)
270  else:
271  rospy.logwarn("Feedback %s of type %s does not exist for this joystick.", feedback.id, feedback.type)
272  self.led_cmd = self.led_values[0] * pow(2, 1) + self.led_values[1] * pow(2, 2)
273  self.led_cmd = self.led_cmd + self.led_values[2] * pow(2, 3) + self.led_values[3] * pow(2, 4)
274  self.new_msg = True
275 
276  def send_cmd(self, ctrl):
277  command = [0x52,
278  0x01,
279  0x00, 0xfe, self.rumble_cmd[1], 0xfe, self.rumble_cmd[0], # rumble values
280  0x00, 0x00, 0x00, 0x00, self.led_cmd,
281  0xff, 0x27, 0x10, 0x00, 0x32, # LED 4
282  0xff, 0x27, 0x10, 0x00, 0x32, # LED 3
283  0xff, 0x27, 0x10, 0x00, 0x32, # LED 2
284  0xff, 0x27, 0x10, 0x00, 0x32, # LED 1
285  0x00, 0x00, 0x00, 0x00, 0x00
286  ]
287  ctrl.send(array('B', command).tostring())
288  self.new_msg = False
289 
290  def run(self, intr, ctrl):
291  activated = False
292  try:
293  self.fullstop()
294  lastactivitytime = lastvalidtime = time.time()
295  while not rospy.is_shutdown():
296  (rd, wr, err) = select.select([intr], [], [], 0.1)
297  curtime = time.time()
298  if len(rd) + len(wr) + len(err) == 0: # Timeout
299  ctrl.send("\x53\xf4\x42\x03\x00\x00") # Try activating the stream.
300  else: # Got a frame.
301  if not activated:
302  self.send_cmd(ctrl)
303  time.sleep(0.5)
304  self.rumble_cmd[1] = 0
305  self.send_cmd(ctrl)
306  print("Connection activated")
307  activated = True
308  try:
309  if(self.new_msg):
310  self.send_cmd(ctrl)
311  rawdata = intr.recv(128)
312  except BluetoothError as s:
313  print("Got Bluetooth error %s. Disconnecting." % s)
314  return
315  if len(rawdata) == 0: # Orderly shutdown of socket
316  print("Joystick shut down the connection, battery may be discharged.")
317  return
318  if not rosgraph.masterapi.is_online():
319  print("The roscore or node shutdown, ps3joy shutting down.")
320  return
321 
322  stepout = self.step(rawdata)
323  if stepout != self.step_error:
324  lastvalidtime = curtime
325  if stepout == self.step_active:
326  lastactivitytime = curtime
327  if curtime - lastactivitytime > self.inactivity_timeout:
328  print("Joystick inactive for %.0f seconds. Disconnecting to save "
329  "battery." % self.inactivity_timeout)
330  return
331  if curtime - lastvalidtime >= 0.1:
332  # Zero all outputs if we don't hear a valid frame for 0.1 to 0.2 seconds
333  self.fullstop()
334  if curtime - lastvalidtime >= 5:
335  # Disconnect if we don't hear a valid frame for 5 seconds
336  print("No valid data for 5 seconds. Disconnecting. This should not happen, please report it.")
337  return
338  time.sleep(0.005) # No need to blaze through the loop when there is an error
339  finally:
340  self.fullstop()
341 
342 
343 class Diagnostics():
344  def __init__(self):
346  0: "Charging",
347  1: "Not Charging"}
349  18: "USB Connection",
350  20: "Rumbling",
351  22: "Bluetooth Connection"}
353  0: "No Charge",
354  1: "20% Charge",
355  2: "40% Charge",
356  3: "60% Charge",
357  4: "80% Charge",
358  5: "100% Charge",
359  238: "Charging"}
360  self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray)
361  self.last_diagnostics_time = rospy.get_rostime()
362 
363  def publish(self, state):
364  STATE_INDEX_CHARGING = 0
365  STATE_INDEX_BATTERY = 1
366  STATE_INDEX_CONNECTION = 2
367 
368  # timed gate: limit to 1 Hz
369  curr_time = rospy.get_rostime()
370  if (curr_time - self.last_diagnostics_time).to_sec() < 1.0:
371  return
372  self.last_diagnostics_time = curr_time
373 
374  # compose diagnostics message
375  diag = DiagnosticArray()
376  diag.header.stamp = curr_time
377  # battery info
378  stat = DiagnosticStatus(name="Battery", level=DiagnosticStatus.OK, message="OK")
379  try:
380  battery_state_code = state[STATE_INDEX_BATTERY]
381  stat.message = self.STATE_TEXTS_BATTERY[battery_state_code]
382  if battery_state_code < 3:
383  stat.level = DiagnosticStatus.WARN
384  if battery_state_code < 1:
385  stat.level = DiagnosticStatus.ERROR
386  stat.message = "Please Recharge Battery (%s)." % self.STATE_TEXTS_BATTERY[battery_state_code]
387  except KeyError as ex:
388  stat.message = "Invalid Battery State %s" % ex
389  rospy.logwarn("Invalid Battery State %s" % ex)
390  stat.level = DiagnosticStatus.ERROR
391  diag.status.append(stat)
392  # connection info
393  stat = DiagnosticStatus(name='ps3joy'": Connection Type", level=DiagnosticStatus.OK, message="OK")
394  try:
395  stat.message = self.STATE_TEXTS_CONNECTION[state[STATE_INDEX_CONNECTION]]
396  except KeyError as ex:
397  stat.message = "Invalid Connection State %s" % ex
398  rospy.logwarn("Invalid Connection State %s" % ex)
399  stat.level = DiagnosticStatus.ERROR
400  diag.status.append(stat)
401  # charging info
402  stat = DiagnosticStatus(name='ps3joy'": Charging State", level=DiagnosticStatus.OK, message="OK")
403  try:
404  stat.message = self.STATE_TEXTS_CHARGING[state[STATE_INDEX_CHARGING]]
405  except KeyError as ex:
406  stat.message = "Invalid Charging State %s" % ex
407  rospy.logwarn("Invalid Charging State %s" % ex)
408  stat.level = DiagnosticStatus.ERROR
409  diag.status.append(stat)
410  # publish message
411  self.diag_pub.publish(diag)
412 
413 
414 class Quit(Exception):
415  def __init__(self, errorcode):
416  Exception.__init__(self)
417  self.errorcode = errorcode
418 
419 
421  # Check if hci0 is up and pscanning, take action as necessary.
422  proc = subprocess.Popen(['hciconfig'], stdout=subprocess.PIPE, stderr=subprocess.PIPE)
423  (out, err) = proc.communicate()
424  if out.find('UP') == -1:
425  os.system("hciconfig hci0 up > /dev/null 2>&1")
426  if out.find('PSCAN') == -1:
427  os.system("hciconfig hci0 pscan > /dev/null 2>&1")
428 
429 
431  def __init__(self, decoder):
432  self.decoder = decoder
433 
434  def prepare_bluetooth_socket(self, port):
435  sock = BluetoothSocket(L2CAP)
436  return self.prepare_socket(sock, port)
437 
438  def prepare_net_socket(self, port):
439  sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
440  return self.prepare_socket(sock, port)
441 
442  def prepare_socket(self, sock, port):
443  first_loop = True
444  while True:
445  try:
446  sock.bind(("", port))
447  except Exception as e:
448  print(repr(e))
449  if first_loop:
450  print("Error binding to socket, will retry every 5 seconds. "
451  "Do you have another ps3joy.py running? This error occurs "
452  "on some distributions. Please read "
453  "http://www.ros.org/wiki/ps3joy/Troubleshooting for solutions.", file=sys.stderr)
454  first_loop = False
455  time.sleep(0.5)
456  continue
457  sock.listen(1)
458  return sock
459 
460  def listen_net(self, intr_port, ctrl_port):
461  intr_sock = self.prepare_net_socket(intr_port)
462  ctrl_sock = self.prepare_net_socket(ctrl_port)
463  self.listen(intr_sock, ctrl_sock)
464 
465  def listen_bluetooth(self):
466  intr_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_INTR)
467  ctrl_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_CTRL)
468  self.listen(intr_sock, ctrl_sock)
469 
470  def listen(self, intr_sock, ctrl_sock):
471  self.n = 0
472  while not rospy.is_shutdown():
473  print("Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button.")
474  try:
475  intr_sock.settimeout(5)
476  ctrl_sock.settimeout(1)
477  while True:
478  try:
479  (intr, (idev, iport)) = intr_sock.accept()
480  break
481  except Exception as e:
482  if str(e) == 'timed out':
484  else:
485  raise
486 
487  try:
488  try:
489  (ctrl, (cdev, cport)) = ctrl_sock.accept()
490  except Exception as e:
491  print("Got interrupt connection without control connection. Giving up on it.",
492  file=sys.stderr)
493  continue
494  try:
495  if idev == cdev:
496  self.decoder.run(intr, ctrl)
497  print("Connection terminated.")
498  quit(0)
499  else:
500  print("Simultaneous connection from two different devices. Ignoring both.",
501  file=sys.stderr)
502  finally:
503  ctrl.close()
504  finally:
505  intr.close()
506  except BadJoystickException:
507  pass
508  except KeyboardInterrupt:
509  print("\nCTRL+C detected. Exiting.")
510  rospy.signal_shutdown("\nCTRL+C detected. Exiting.")
511  quit(0)
512  except Exception as e:
513  traceback.print_exc()
514  print("Caught exception: %s" % str(e), file=sys.stderr)
515  time.sleep(1)
516 
517 
518 def usage(errcode):
519  print("usage: ps3joy.py [" + inactivity_timout_string + "=<n>] [" + no_disable_bluetoothd_string + "] "
520  "[" + redirect_output_string + "]=<f>")
521  print("<n>: inactivity timeout in seconds (saves battery life).")
522  print("<f>: file name to redirect output to.")
523  print("Unless "+no_disable_bluetoothd_string+" is specified, bluetoothd will be stopped.")
524  raise Quit(errcode)
525 
526 
527 def is_arg_with_param(arg, prefix):
528  if not arg.startswith(prefix):
529  return False
530  if not arg.startswith(prefix+"="):
531  print("Expected '=' after "+prefix)
532  print()
533  usage(1)
534  return True
535 
536 
537 if __name__ == "__main__":
538  errorcode = 0
539  try:
540  inactivity_timeout = float(1e3000)
541  disable_bluetoothd = True
542  deamon = False
543  for arg in sys.argv[1:]: # Be very tolerant in case we are roslaunched.
544  if arg == "--help":
545  usage(0)
546  elif is_arg_with_param(arg, inactivity_timout_string):
547  str_value = arg[len(inactivity_timout_string)+1:]
548  try:
549  inactivity_timeout = float(str_value)
550  if inactivity_timeout < 0:
551  print("Inactivity timeout must be positive.")
552  print()
553  usage(1)
554  except ValueError:
555  print("Error parsing inactivity timeout: "+str_value)
556  print()
557  usage(1)
558  elif arg == no_disable_bluetoothd_string:
559  disable_bluetoothd = False
560  elif is_arg_with_param(arg, redirect_output_string):
561  str_value = arg[len(redirect_output_string)+1:]
562  try:
563  print("Redirecting output to:", str_value)
564  sys.stdout = open(str_value, "a", 1)
565  except IOError as e:
566  print("Error opening file to redirect output:", str_value)
567  raise Quit(1)
568  sys.stderr = sys.stdout
569  else:
570  print("Ignoring parameter: '%s'" % arg)
571 
572  # If the user does not have HW permissions indicate that ps3joy must be run as root
573  if os.getuid() != 0:
574  print("ps3joy.py must be run as root.", file=sys.stderr)
575  quit(1)
576  if disable_bluetoothd:
577  os.system("/etc/init.d/bluetooth stop > /dev/null 2>&1")
578  time.sleep(1) # Give the socket time to be available.
579  try:
580  while os.system("hciconfig hci0 > /dev/null 2>&1") != 0:
581  print("No bluetooth dongle found or bluez rosdep not installed. "
582  "Will retry in 5 seconds.", file=sys.stderr)
583  time.sleep(5)
584  if inactivity_timeout == float(1e3000):
585  print("No inactivity timeout was set. (Run with --help for details.)")
586  else:
587  print("Inactivity timeout set to %.0f seconds." % inactivity_timeout)
588  cm = connection_manager(decoder(deamon, inactivity_timeout=inactivity_timeout))
589  cm.listen_bluetooth()
590  finally:
591  if disable_bluetoothd:
592  os.system("/etc/init.d/bluetooth start > /dev/null 2>&1")
593  except Quit as e:
594  errorcode = e.errorcode
595  except KeyboardInterrupt:
596  print("\nCTRL+C detected. Exiting.")
597  rospy.signal_shutdown("\nCTRL+C detected. Exiting.")
598  exit(errorcode)
ps3joy_node.decoder.core_down
core_down
Definition: ps3joy_node.py:190
ps3joy_node.Diagnostics.publish
def publish(self, state)
Definition: ps3joy_node.py:363
ps3joy_node.decoder.step_idle
int step_idle
Definition: ps3joy_node.py:180
ps3joy_node.connection_manager.__init__
def __init__(self, decoder)
Definition: ps3joy_node.py:431
ps3joy_node.BadJoystickException.__init__
def __init__(self)
Definition: ps3joy_node.py:144
ps3joy_node.decoder.new_msg
new_msg
Definition: ps3joy_node.py:274
ps3joy_node.decoder.diagnostics
diagnostics
Definition: ps3joy_node.py:186
ps3joy_node.uinputjoy.type
type
Definition: ps3joy_node.py:126
ps3joy_node.connection_manager.decoder
decoder
Definition: ps3joy_node.py:432
ps3joy_node.Diagnostics.STATE_TEXTS_CHARGING
STATE_TEXTS_CHARGING
Definition: ps3joy_node.py:345
ps3joy_node.uinput
Definition: ps3joy_node.py:61
ps3joy_node.uinputjoy.__init__
def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat)
Definition: ps3joy_node.py:79
ps3joy_node.decoder.step_error
int step_error
Definition: ps3joy_node.py:181
ps3joy_node.decoder.rumble_cmd
rumble_cmd
Definition: ps3joy_node.py:188
ps3joy_node.connection_manager.prepare_socket
def prepare_socket(self, sock, port)
Definition: ps3joy_node.py:442
ps3joy_node.connection_manager.listen_net
def listen_net(self, intr_port, ctrl_port)
Definition: ps3joy_node.py:460
ps3joy_node.decoder.send_cmd
def send_cmd(self, ctrl)
Definition: ps3joy_node.py:276
ps3joy_node.decoder.led_values
led_values
Definition: ps3joy_node.py:187
ps3joy_node.decoder.deamon
deamon
Definition: ps3joy_node.py:177
ps3joy_node.BadJoystickException
Definition: ps3joy_node.py:143
ps3joy_node.decoder.outlen
outlen
Definition: ps3joy_node.py:175
ps3joy_node.decoder.fullstop
def fullstop(self)
Definition: ps3joy_node.py:261
ps3joy_node.Diagnostics.STATE_TEXTS_CONNECTION
STATE_TEXTS_CONNECTION
Definition: ps3joy_node.py:348
ps3joy_node.decoder.step
def step(self, rawdata)
Definition: ps3joy_node.py:226
ps3joy_node.uinputjoy.update
def update(self, value)
Definition: ps3joy_node.py:129
ps3joy_node.decoder.init_ros
def init_ros(self)
Definition: ps3joy_node.py:183
ps3joy_node.decoder.set_feedback
def set_feedback(self, msg)
Definition: ps3joy_node.py:264
ps3joy_node.connection_manager
Definition: ps3joy_node.py:430
ps3joy_node.connection_manager.prepare_net_socket
def prepare_net_socket(self, port)
Definition: ps3joy_node.py:438
ps3joy_node.connection_manager.prepare_bluetooth_socket
def prepare_bluetooth_socket(self, port)
Definition: ps3joy_node.py:434
ps3joy_node.decoder.inactivity_timeout
inactivity_timeout
Definition: ps3joy_node.py:176
ps3joy_node.decoder.run
def run(self, intr, ctrl)
Definition: ps3joy_node.py:290
ps3joy_node.decoder
Definition: ps3joy_node.py:148
ps3joy_node.decoder.step_active
int step_active
Definition: ps3joy_node.py:179
ps3joy_node.decoder.axmid
axmid
Definition: ps3joy_node.py:173
ps3joy_node.Quit
Definition: ps3joy_node.py:414
ps3joy_node.check_hci_status
def check_hci_status()
Definition: ps3joy_node.py:420
ps3joy_node.connection_manager.listen_bluetooth
def listen_bluetooth(self)
Definition: ps3joy_node.py:465
ps3joy_node.Quit.errorcode
errorcode
Definition: ps3joy_node.py:417
ps3joy_node.decoder.joy
joy
Definition: ps3joy_node.py:172
ps3joy_node.connection_manager.listen
def listen(self, intr_sock, ctrl_sock)
Definition: ps3joy_node.py:470
ps3joy_node.uinputjoy.open_uinput
def open_uinput(self)
Definition: ps3joy_node.py:70
ps3joy_node.uinputjoy.code
code
Definition: ps3joy_node.py:127
ps3joy_node.uinputjoy.file
file
Definition: ps3joy_node.py:80
ps3joy_node.Diagnostics.last_diagnostics_time
last_diagnostics_time
Definition: ps3joy_node.py:361
ps3joy_node.connection_manager.n
n
Definition: ps3joy_node.py:471
ps3joy_node.decoder.__init__
def __init__(self, deamon, inactivity_timeout=float(1e3000))
Definition: ps3joy_node.py:149
ps3joy_node.Diagnostics
Definition: ps3joy_node.py:343
ps3joy_node.uinputjoy.value
value
Definition: ps3joy_node.py:125
ps3joy_node.Diagnostics.diag_pub
diag_pub
Definition: ps3joy_node.py:360
ps3joy_node.Diagnostics.STATE_TEXTS_BATTERY
STATE_TEXTS_BATTERY
Definition: ps3joy_node.py:352
ps3joy_node.decoder.led_cmd
led_cmd
Definition: ps3joy_node.py:189
ps3joy_node.uinputjoy
Definition: ps3joy_node.py:69
ps3joy_node.is_arg_with_param
def is_arg_with_param(arg, prefix)
Definition: ps3joy_node.py:527
ps3joy_node.usage
def usage(errcode)
Definition: ps3joy_node.py:518
ps3joy_node.Diagnostics.__init__
def __init__(self)
Definition: ps3joy_node.py:344
ps3joy_node.Quit.__init__
def __init__(self, errorcode)
Definition: ps3joy_node.py:415


ps3joy
Author(s): Blaise Gassend, pascal@pabr.org, Melonee Wise
autogenerated on Sun May 2 2021 02:17:55