34 from __future__
import print_function
37 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus, KeyValue
39 from bluetooth
import *
48 from array
import array
49 import sensor_msgs.msg
50 import rosgraph.masterapi
52 roslib.load_manifest(
'ps3joy')
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"
71 for name
in [
"/dev/input/uinput",
"/dev/misc/uinput",
"/dev/uinput"]:
73 return os.open(name, os.O_WRONLY)
75 except Exception
as e:
79 def __init__(self, buttons, axes, axmin, axmax, axfuzz, axflat):
82 print(
"Trying to modprobe uinput.", file=sys.stderr)
83 os.system(
"modprobe uinput > /dev/null 2>&1")
87 print(
"Can't open uinput device. Is it accessible by this user? Did you mean to run as root?",
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'
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]
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)))
114 fcntl.ioctl(self.
file, UI_SET_EVBIT, uinput.EV_KEY)
117 fcntl.ioctl(self.
file, UI_SET_KEYBIT, b)
120 fcntl.ioctl(self.
file, UI_SET_EVBIT, uinput.EV_ABS)
121 fcntl.ioctl(self.
file, UI_SET_ABSBIT, a)
123 fcntl.ioctl(self.
file, UI_DEV_CREATE)
125 self.
value = [
None] * (len(buttons) + len(axes))
126 self.
type = [uinput.EV_KEY] * len(buttons) + [uinput.EV_ABS] * len(axes)
130 input_event =
"LLHHi"
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)
145 Exception.__init__(self,
"Unsupported joystick.")
149 def __init__(self, deamon, inactivity_timeout=float(1e3000)):
160 buttons = range(0x100, 0x111)
166 for i
in range(-4, 0):
170 for i
in range(4, len(axmin) - 4):
173 self.
axmid = [sum(pair) / 2
for pair
in zip(axmin, axmax)]
184 rospy.init_node(
'ps3joy', anonymous=
True, disable_signals=
True)
185 rospy.Subscriber(
"joy/set_feedback", sensor_msgs.msg.JoyFeedbackArray, self.
set_feedback)
227 if len(rawdata) == 50:
228 joy_coding =
"!1B2x3B1x4B4x12B3x1B1B1B9x4H"
229 all_data = list(struct.unpack(joy_coding, rawdata))
230 state_data = all_data[20:23]
231 data = all_data[0:20]+all_data[23:]
235 print(
"Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?" % prefix,
239 for j
in range(0, 2):
240 curbyte = data.pop(0)
241 for k
in range(0, 8):
242 out.append(int((curbyte & (1 << k)) != 0))
246 abs(out[17:][i] - self.
axmid[i]) > 20
for i
in range(0, len(out) - 17 - 4)
249 if any(out[0:17])
or any(axis_motion):
252 elif len(rawdata) == 13:
253 print(
"Your bluetooth adapter is not supported. Does it support Bluetooth 2.0?",
257 print(
"Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?"
258 % len(rawdata), file=sys.stderr)
262 self.
joy.update([0] * 17 + self.
axmid)
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)
271 rospy.logwarn(
"Feedback %s of type %s does not exist for this joystick.", feedback.id, feedback.type)
280 0x00, 0x00, 0x00, 0x00, self.
led_cmd,
281 0xff, 0x27, 0x10, 0x00, 0x32,
282 0xff, 0x27, 0x10, 0x00, 0x32,
283 0xff, 0x27, 0x10, 0x00, 0x32,
284 0xff, 0x27, 0x10, 0x00, 0x32,
285 0x00, 0x00, 0x00, 0x00, 0x00
287 ctrl.send(array(
'B', command).tostring())
290 def run(self, intr, ctrl):
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:
299 ctrl.send(
"\x53\xf4\x42\x03\x00\x00")
306 print(
"Connection activated")
311 rawdata = intr.recv(128)
312 except BluetoothError
as 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.")
322 stepout = self.
step(rawdata)
324 lastvalidtime = curtime
326 lastactivitytime = curtime
328 print(
"Joystick inactive for %.0f seconds. Disconnecting to save "
331 if curtime - lastvalidtime >= 0.1:
334 if curtime - lastvalidtime >= 5:
336 print(
"No valid data for 5 seconds. Disconnecting. This should not happen, please report it.")
349 18:
"USB Connection",
351 22:
"Bluetooth Connection"}
360 self.
diag_pub = rospy.Publisher(
'/diagnostics', DiagnosticArray)
364 STATE_INDEX_CHARGING = 0
365 STATE_INDEX_BATTERY = 1
366 STATE_INDEX_CONNECTION = 2
369 curr_time = rospy.get_rostime()
375 diag = DiagnosticArray()
376 diag.header.stamp = curr_time
378 stat = DiagnosticStatus(name=
"Battery", level=DiagnosticStatus.OK, message=
"OK")
380 battery_state_code = state[STATE_INDEX_BATTERY]
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)
393 stat = DiagnosticStatus(name=
'ps3joy'": Connection Type", level=DiagnosticStatus.OK, message=
"OK")
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)
402 stat = DiagnosticStatus(name=
'ps3joy'": Charging State", level=DiagnosticStatus.OK, message=
"OK")
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)
416 Exception.__init__(self)
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")
435 sock = BluetoothSocket(L2CAP)
439 sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
446 sock.bind((
"", port))
447 except Exception
as e:
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)
463 self.
listen(intr_sock, ctrl_sock)
468 self.
listen(intr_sock, ctrl_sock)
472 while not rospy.is_shutdown():
473 print(
"Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button.")
475 intr_sock.settimeout(5)
476 ctrl_sock.settimeout(1)
479 (intr, (idev, iport)) = intr_sock.accept()
481 except Exception
as e:
482 if str(e) ==
'timed out':
489 (ctrl, (cdev, cport)) = ctrl_sock.accept()
490 except Exception
as e:
491 print(
"Got interrupt connection without control connection. Giving up on it.",
497 print(
"Connection terminated.")
500 print(
"Simultaneous connection from two different devices. Ignoring both.",
506 except BadJoystickException:
508 except KeyboardInterrupt:
509 print(
"\nCTRL+C detected. Exiting.")
510 rospy.signal_shutdown(
"\nCTRL+C detected. Exiting.")
512 except Exception
as e:
513 traceback.print_exc()
514 print(
"Caught exception: %s" % str(e), file=sys.stderr)
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.")
528 if not arg.startswith(prefix):
530 if not arg.startswith(prefix+
"="):
531 print(
"Expected '=' after "+prefix)
537 if __name__ ==
"__main__":
540 inactivity_timeout = float(1e3000)
541 disable_bluetoothd =
True
543 for arg
in sys.argv[1:]:
547 str_value = arg[len(inactivity_timout_string)+1:]
549 inactivity_timeout = float(str_value)
550 if inactivity_timeout < 0:
551 print(
"Inactivity timeout must be positive.")
555 print(
"Error parsing inactivity timeout: "+str_value)
558 elif arg == no_disable_bluetoothd_string:
559 disable_bluetoothd =
False
561 str_value = arg[len(redirect_output_string)+1:]
563 print(
"Redirecting output to:", str_value)
564 sys.stdout = open(str_value,
"a", 1)
566 print(
"Error opening file to redirect output:", str_value)
568 sys.stderr = sys.stdout
570 print(
"Ignoring parameter: '%s'" % arg)
574 print(
"ps3joy.py must be run as root.", file=sys.stderr)
576 if disable_bluetoothd:
577 os.system(
"/etc/init.d/bluetooth stop > /dev/null 2>&1")
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)
584 if inactivity_timeout == float(1e3000):
585 print(
"No inactivity timeout was set. (Run with --help for details.)")
587 print(
"Inactivity timeout set to %.0f seconds." % inactivity_timeout)
589 cm.listen_bluetooth()
591 if disable_bluetoothd:
592 os.system(
"/etc/init.d/bluetooth start > /dev/null 2>&1")
594 errorcode = e.errorcode
595 except KeyboardInterrupt:
596 print(
"\nCTRL+C detected. Exiting.")
597 rospy.signal_shutdown(
"\nCTRL+C detected. Exiting.")