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  try:
185  rospy.init_node('ps3joy', anonymous=True, disable_signals=True)
186  except:
187  print("rosnode init failed")
188  rospy.Subscriber("joy/set_feedback", sensor_msgs.msg.JoyFeedbackArray, self.set_feedback)
190  self.led_values = [1, 0, 0, 0]
191  self.rumble_cmd = [0, 255]
192  self.led_cmd = 2
193  self.core_down = False
194 
195  # ********************************************************************************
196  # Raw Data Format
197  # unsigned char ReportType; //Report Type 01
198  # unsigned char Reserved1; // Unknown
199  # unsigned int ButtonState; // Main buttons
200  # unsigned char PSButtonState; // PS button
201  # unsigned char Reserved2; // Unknown
202  # unsigned char LeftStickX; // left Joystick X axis 0 - 255, 128 is mid
203  # unsigned char LeftStickY; // left Joystick Y axis 0 - 255, 128 is mid
204  # unsigned char RightStickX; // right Joystick X axis 0 - 255, 128 is mid
205  # unsigned char RightStickY; // right Joystick Y axis 0 - 255, 128 is mid
206  # unsigned char Reserved3[4]; // Unknown
207  # unsigned char PressureUp; // digital Pad Up button Pressure 0 - 255
208  # unsigned char PressureRight; // digital Pad Right button Pressure 0 - 255
209  # unsigned char PressureDown; // digital Pad Down button Pressure 0 - 255
210  # unsigned char PressureLeft; // digital Pad Left button Pressure 0 - 255
211  # unsigned char PressureL2; // digital Pad L2 button Pressure 0 - 255
212  # unsigned char PressureR2; // digital Pad R2 button Pressure 0 - 255
213  # unsigned char PressureL1; // digital Pad L1 button Pressure 0 - 255
214  # unsigned char PressureR1; // digital Pad R1 button Pressure 0 - 255
215  # unsigned char PressureTriangle; // digital Pad Triangle button Pressure 0 - 255
216  # unsigned char PressureCircle; // digital Pad Circle button Pressure 0 - 255
217  # unsigned char PressureCross; // digital Pad Cross button Pressure 0 - 255
218  # unsigned char PressureSquare; // digital Pad Square button Pressure 0 - 255
219  # unsigned char Reserved4[3]; // Unknown
220  # unsigned char Charge; // charging status ? 02 = charge, 03 = normal
221  # unsigned char Power; // Battery status
222  # unsigned char Connection; // Connection Type
223  # unsigned char Reserved5[9]; // Unknown
224  # unsigned int AccelerometerX; // X axis accelerometer Big Endian 0 - 1023
225  # unsigned int Accelero // Y axis accelerometer Big Endian 0 - 1023
226  # unsigned int AccelerometerZ; // Z axis accelerometer Big Endian 0 - 1023
227  # unsigned int GyrometerX; // Z axis Gyro Big Endian 0 - 1023
228  # *********************************************************************************
229  def step(self, rawdata): # Returns true if the packet was legal
230  if len(rawdata) == 50:
231  joy_coding = "!1B2x3B1x4B4x12B3x1B1B1B9x4H"
232  all_data = list(struct.unpack(joy_coding, rawdata)) # removing power data
233  state_data = all_data[20:23]
234  data = all_data[0:20]+all_data[23:]
235  prefix = data.pop(0)
236  self.diagnostics.publish(state_data)
237  if prefix != 161:
238  print("Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?" % prefix,
239  file=sys.stderr)
240  return self.step_error
241  out = []
242  for j in range(0, 2): # Split out the buttons.
243  curbyte = data.pop(0)
244  for k in range(0, 8):
245  out.append(int((curbyte & (1 << k)) != 0))
246  out = out + data
247  self.joy.update(out)
248  axis_motion = [
249  abs(out[17:][i] - self.axmid[i]) > 20 for i in range(0, len(out) - 17 - 4)
250  ] # 17 buttons, 4 inertial sensors
251 
252  if any(out[0:17]) or any(axis_motion):
253  return self.step_active
254  return self.step_idle
255  elif len(rawdata) == 13:
256  print("Your bluetooth adapter is not supported. Does it support Bluetooth 2.0?",
257  file=sys.stderr)
258  raise BadJoystickException()
259  else:
260  print("Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?"
261  % len(rawdata), file=sys.stderr)
262  return self.step_error
263 
264  def fullstop(self):
265  self.joy.update([0] * 17 + self.axmid)
266 
267  def set_feedback(self, msg):
268  for feedback in msg.array:
269  if feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_LED and feedback.id < 4:
270  self.led_values[feedback.id] = int(round(feedback.intensity))
271  elif feedback.type == sensor_msgs.msg.JoyFeedback.TYPE_RUMBLE and feedback.id < 2:
272  self.rumble_cmd[feedback.id] = int(feedback.intensity*255)
273  else:
274  rospy.logwarn("Feedback %s of type %s does not exist for this joystick.", feedback.id, feedback.type)
275  self.led_cmd = self.led_values[0] * pow(2, 1) + self.led_values[1] * pow(2, 2)
276  self.led_cmd = self.led_cmd + self.led_values[2] * pow(2, 3) + self.led_values[3] * pow(2, 4)
277  self.new_msg = True
278 
279  def send_cmd(self, ctrl):
280  command = [0x52,
281  0x01,
282  0x00, 0xfe, self.rumble_cmd[1], 0xfe, self.rumble_cmd[0], # rumble values
283  0x00, 0x00, 0x00, 0x00, self.led_cmd,
284  0xff, 0x27, 0x10, 0x00, 0x32, # LED 4
285  0xff, 0x27, 0x10, 0x00, 0x32, # LED 3
286  0xff, 0x27, 0x10, 0x00, 0x32, # LED 2
287  0xff, 0x27, 0x10, 0x00, 0x32, # LED 1
288  0x00, 0x00, 0x00, 0x00, 0x00
289  ]
290  ctrl.send(array('B', command).tostring())
291  self.new_msg = False
292 
293  def run(self, intr, ctrl):
294  activated = False
295  try:
296  self.fullstop()
297  lastactivitytime = lastvalidtime = time.time()
298  while not rospy.is_shutdown():
299  (rd, wr, err) = select.select([intr], [], [], 0.1)
300  curtime = time.time()
301  if len(rd) + len(wr) + len(err) == 0: # Timeout
302  ctrl.send("\x53\xf4\x42\x03\x00\x00") # Try activating the stream.
303  else: # Got a frame.
304  if not activated:
305  self.send_cmd(ctrl)
306  time.sleep(0.5)
307  self.rumble_cmd[1] = 0
308  self.send_cmd(ctrl)
309  print("Connection activated")
310  activated = True
311  try:
312  if(self.new_msg):
313  self.send_cmd(ctrl)
314  rawdata = intr.recv(128)
315  except BluetoothError as s:
316  print("Got Bluetooth error %s. Disconnecting." % s)
317  return
318  if len(rawdata) == 0: # Orderly shutdown of socket
319  print("Joystick shut down the connection, battery may be discharged.")
320  return
321  if not rosgraph.masterapi.is_online():
322  print("The roscore or node shutdown, ps3joy shutting down.")
323  return
324 
325  stepout = self.step(rawdata)
326  if stepout != self.step_error:
327  lastvalidtime = curtime
328  if stepout == self.step_active:
329  lastactivitytime = curtime
330  if curtime - lastactivitytime > self.inactivity_timeout:
331  print("Joystick inactive for %.0f seconds. Disconnecting to save "
332  "battery." % self.inactivity_timeout)
333  return
334  if curtime - lastvalidtime >= 0.1:
335  # Zero all outputs if we don't hear a valid frame for 0.1 to 0.2 seconds
336  self.fullstop()
337  if curtime - lastvalidtime >= 5:
338  # Disconnect if we don't hear a valid frame for 5 seconds
339  print("No valid data for 5 seconds. Disconnecting. This should not happen, please report it.")
340  return
341  time.sleep(0.005) # No need to blaze through the loop when there is an error
342  finally:
343  self.fullstop()
344 
345 
346 class Diagnostics():
347  def __init__(self):
349  0: "Charging",
350  1: "Not Charging"}
352  18: "USB Connection",
353  20: "Rumbling",
354  22: "Bluetooth Connection"}
356  0: "No Charge",
357  1: "20% Charge",
358  2: "40% Charge",
359  3: "60% Charge",
360  4: "80% Charge",
361  5: "100% Charge",
362  238: "Charging"}
363  self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray)
364  self.last_diagnostics_time = rospy.get_rostime()
365 
366  def publish(self, state):
367  STATE_INDEX_CHARGING = 0
368  STATE_INDEX_BATTERY = 1
369  STATE_INDEX_CONNECTION = 2
370 
371  # timed gate: limit to 1 Hz
372  curr_time = rospy.get_rostime()
373  if (curr_time - self.last_diagnostics_time).to_sec() < 1.0:
374  return
375  self.last_diagnostics_time = curr_time
376 
377  # compose diagnostics message
378  diag = DiagnosticArray()
379  diag.header.stamp = curr_time
380  # battery info
381  stat = DiagnosticStatus(name="Battery", level=DiagnosticStatus.OK, message="OK")
382  try:
383  battery_state_code = state[STATE_INDEX_BATTERY]
384  stat.message = self.STATE_TEXTS_BATTERY[battery_state_code]
385  if battery_state_code < 3:
386  stat.level = DiagnosticStatus.WARN
387  if battery_state_code < 1:
388  stat.level = DiagnosticStatus.ERROR
389  stat.message = "Please Recharge Battery (%s)." % self.STATE_TEXTS_BATTERY[battery_state_code]
390  except KeyError as ex:
391  stat.message = "Invalid Battery State %s" % ex
392  rospy.logwarn("Invalid Battery State %s" % ex)
393  stat.level = DiagnosticStatus.ERROR
394  diag.status.append(stat)
395  # connection info
396  stat = DiagnosticStatus(name='ps3joy'": Connection Type", level=DiagnosticStatus.OK, message="OK")
397  try:
398  stat.message = self.STATE_TEXTS_CONNECTION[state[STATE_INDEX_CONNECTION]]
399  except KeyError as ex:
400  stat.message = "Invalid Connection State %s" % ex
401  rospy.logwarn("Invalid Connection State %s" % ex)
402  stat.level = DiagnosticStatus.ERROR
403  diag.status.append(stat)
404  # charging info
405  stat = DiagnosticStatus(name='ps3joy'": Charging State", level=DiagnosticStatus.OK, message="OK")
406  try:
407  stat.message = self.STATE_TEXTS_CHARGING[state[STATE_INDEX_CHARGING]]
408  except KeyError as ex:
409  stat.message = "Invalid Charging State %s" % ex
410  rospy.logwarn("Invalid Charging State %s" % ex)
411  stat.level = DiagnosticStatus.ERROR
412  diag.status.append(stat)
413  # publish message
414  self.diag_pub.publish(diag)
415 
416 
417 class Quit(Exception):
418  def __init__(self, errorcode):
419  Exception.__init__(self)
420  self.errorcode = errorcode
421 
422 
424  # Check if hci0 is up and pscanning, take action as necessary.
425  proc = subprocess.Popen(['hciconfig'], stdout=subprocess.PIPE, stderr=subprocess.PIPE)
426  (out, err) = proc.communicate()
427  if out.find('UP') == -1:
428  os.system("hciconfig hci0 up > /dev/null 2>&1")
429  if out.find('PSCAN') == -1:
430  os.system("hciconfig hci0 pscan > /dev/null 2>&1")
431 
432 
434  def __init__(self, decoder):
435  self.decoder = decoder
436 
437  def prepare_bluetooth_socket(self, port):
438  sock = BluetoothSocket(L2CAP)
439  return self.prepare_socket(sock, port)
440 
441  def prepare_net_socket(self, port):
442  sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
443  return self.prepare_socket(sock, port)
444 
445  def prepare_socket(self, sock, port):
446  first_loop = True
447  while True:
448  try:
449  sock.bind(("", port))
450  except Exception as e:
451  print(repr(e))
452  if first_loop:
453  print("Error binding to socket, will retry every 5 seconds. "
454  "Do you have another ps3joy.py running? This error occurs "
455  "on some distributions. Please read "
456  "http://www.ros.org/wiki/ps3joy/Troubleshooting for solutions.", file=sys.stderr)
457  first_loop = False
458  time.sleep(0.5)
459  continue
460  sock.listen(1)
461  return sock
462 
463  def listen_net(self, intr_port, ctrl_port):
464  intr_sock = self.prepare_net_socket(intr_port)
465  ctrl_sock = self.prepare_net_socket(ctrl_port)
466  self.listen(intr_sock, ctrl_sock)
467 
468  def listen_bluetooth(self):
469  intr_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_INTR)
470  ctrl_sock = self.prepare_bluetooth_socket(L2CAP_PSM_HIDP_CTRL)
471  self.listen(intr_sock, ctrl_sock)
472 
473  def listen(self, intr_sock, ctrl_sock):
474  self.n = 0
475  while not rospy.is_shutdown():
476  print("Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button.")
477  try:
478  intr_sock.settimeout(5)
479  ctrl_sock.settimeout(1)
480  while True:
481  try:
482  (intr, (idev, iport)) = intr_sock.accept()
483  break
484  except Exception as e:
485  if str(e) == 'timed out':
487  else:
488  raise
489 
490  try:
491  try:
492  (ctrl, (cdev, cport)) = ctrl_sock.accept()
493  except Exception as e:
494  print("Got interrupt connection without control connection. Giving up on it.",
495  file=sys.stderr)
496  continue
497  try:
498  if idev == cdev:
499  self.decoder.run(intr, ctrl)
500  print("Connection terminated.")
501  quit(0)
502  else:
503  print("Simultaneous connection from two different devices. Ignoring both.",
504  file=sys.stderr)
505  finally:
506  ctrl.close()
507  finally:
508  intr.close()
509  except BadJoystickException:
510  pass
511  except KeyboardInterrupt:
512  print("\nCTRL+C detected. Exiting.")
513  rospy.signal_shutdown("\nCTRL+C detected. Exiting.")
514  quit(0)
515  except Exception as e:
516  traceback.print_exc()
517  print("Caught exception: %s" % str(e), file=sys.stderr)
518  time.sleep(1)
519 
520 
521 def usage(errcode):
522  print("usage: ps3joy.py [" + inactivity_timout_string + "=<n>] [" + no_disable_bluetoothd_string + "] "
523  "[" + redirect_output_string + "]=<f>")
524  print("<n>: inactivity timeout in seconds (saves battery life).")
525  print("<f>: file name to redirect output to.")
526  print("Unless "+no_disable_bluetoothd_string+" is specified, bluetoothd will be stopped.")
527  raise Quit(errcode)
528 
529 
530 def is_arg_with_param(arg, prefix):
531  if not arg.startswith(prefix):
532  return False
533  if not arg.startswith(prefix+"="):
534  print("Expected '=' after "+prefix)
535  print()
536  usage(1)
537  return True
538 
539 
540 if __name__ == "__main__":
541  errorcode = 0
542  try:
543  inactivity_timeout = float(1e3000)
544  disable_bluetoothd = True
545  deamon = False
546  for arg in sys.argv[1:]: # Be very tolerant in case we are roslaunched.
547  if arg == "--help":
548  usage(0)
549  elif is_arg_with_param(arg, inactivity_timout_string):
550  str_value = arg[len(inactivity_timout_string)+1:]
551  try:
552  inactivity_timeout = float(str_value)
553  if inactivity_timeout < 0:
554  print("Inactivity timeout must be positive.")
555  print()
556  usage(1)
557  except ValueError:
558  print("Error parsing inactivity timeout: "+str_value)
559  print()
560  usage(1)
561  elif arg == no_disable_bluetoothd_string:
562  disable_bluetoothd = False
563  elif is_arg_with_param(arg, redirect_output_string):
564  str_value = arg[len(redirect_output_string)+1:]
565  try:
566  print("Redirecting output to:", str_value)
567  sys.stdout = open(str_value, "a", 1)
568  except IOError as e:
569  print("Error opening file to redirect output:", str_value)
570  raise Quit(1)
571  sys.stderr = sys.stdout
572  else:
573  print("Ignoring parameter: '%s'" % arg)
574 
575  # If the user does not have HW permissions indicate that ps3joy must be run as root
576  if os.getuid() != 0:
577  print("ps3joy.py must be run as root.", file=sys.stderr)
578  quit(1)
579  if disable_bluetoothd:
580  os.system("/etc/init.d/bluetooth stop > /dev/null 2>&1")
581  time.sleep(1) # Give the socket time to be available.
582  try:
583  while os.system("hciconfig hci0 > /dev/null 2>&1") != 0:
584  print("No bluetooth dongle found or bluez rosdep not installed. "
585  "Will retry in 5 seconds.", file=sys.stderr)
586  time.sleep(5)
587  if inactivity_timeout == float(1e3000):
588  print("No inactivity timeout was set. (Run with --help for details.)")
589  else:
590  print("Inactivity timeout set to %.0f seconds." % inactivity_timeout)
591  cm = connection_manager(decoder(deamon, inactivity_timeout=inactivity_timeout))
592  cm.listen_bluetooth()
593  finally:
594  if disable_bluetoothd:
595  os.system("/etc/init.d/bluetooth start > /dev/null 2>&1")
596  except Quit as e:
597  errorcode = e.errorcode
598  except KeyboardInterrupt:
599  print("\nCTRL+C detected. Exiting.")
600  rospy.signal_shutdown("\nCTRL+C detected. Exiting.")
601  exit(errorcode)
def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat)
Definition: ps3joy_node.py:79
def __init__(self, deamon, inactivity_timeout=float(1e3000))
Definition: ps3joy_node.py:149
def update(self, value)
Definition: ps3joy_node.py:129
def usage(errcode)
Definition: ps3joy_node.py:521
def step(self, rawdata)
Definition: ps3joy_node.py:229
def send_cmd(self, ctrl)
Definition: ps3joy_node.py:279
def listen_net(self, intr_port, ctrl_port)
Definition: ps3joy_node.py:463
def __init__(self, decoder)
Definition: ps3joy_node.py:434
def check_hci_status()
Definition: ps3joy_node.py:423
def listen(self, intr_sock, ctrl_sock)
Definition: ps3joy_node.py:473
def publish(self, state)
Definition: ps3joy_node.py:366
def is_arg_with_param(arg, prefix)
Definition: ps3joy_node.py:530
def run(self, intr, ctrl)
Definition: ps3joy_node.py:293
def prepare_net_socket(self, port)
Definition: ps3joy_node.py:441
def set_feedback(self, msg)
Definition: ps3joy_node.py:267
def prepare_bluetooth_socket(self, port)
Definition: ps3joy_node.py:437
def prepare_socket(self, sock, port)
Definition: ps3joy_node.py:445
def __init__(self, errorcode)
Definition: ps3joy_node.py:418


ps3joy
Author(s): Blaise Gassend, pascal@pabr.org, Melonee Wise
autogenerated on Mon Feb 28 2022 22:37:02