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)]
185 rospy.init_node(
'ps3joy', anonymous=
True, disable_signals=
True)
187 print(
"rosnode init failed")
188 rospy.Subscriber(
"joy/set_feedback", sensor_msgs.msg.JoyFeedbackArray, self.
set_feedback)
230 if len(rawdata) == 50:
231 joy_coding =
"!1B2x3B1x4B4x12B3x1B1B1B9x4H" 232 all_data = list(struct.unpack(joy_coding, rawdata))
233 state_data = all_data[20:23]
234 data = all_data[0:20]+all_data[23:]
238 print(
"Unexpected prefix (%i). Is this a PS3 Dual Shock or Six Axis?" % prefix,
242 for j
in range(0, 2):
243 curbyte = data.pop(0)
244 for k
in range(0, 8):
245 out.append(int((curbyte & (1 << k)) != 0))
249 abs(out[17:][i] - self.
axmid[i]) > 20
for i
in range(0, len(out) - 17 - 4)
252 if any(out[0:17])
or any(axis_motion):
255 elif len(rawdata) == 13:
256 print(
"Your bluetooth adapter is not supported. Does it support Bluetooth 2.0?",
260 print(
"Unexpected packet length (%i). Is this a PS3 Dual Shock or Six Axis?" 261 % len(rawdata), file=sys.stderr)
265 self.
joy.update([0] * 17 + self.
axmid)
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)
274 rospy.logwarn(
"Feedback %s of type %s does not exist for this joystick.", feedback.id, feedback.type)
283 0x00, 0x00, 0x00, 0x00, self.
led_cmd,
284 0xff, 0x27, 0x10, 0x00, 0x32,
285 0xff, 0x27, 0x10, 0x00, 0x32,
286 0xff, 0x27, 0x10, 0x00, 0x32,
287 0xff, 0x27, 0x10, 0x00, 0x32,
288 0x00, 0x00, 0x00, 0x00, 0x00
290 ctrl.send(array(
'B', command).tostring())
293 def run(self, intr, ctrl):
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:
302 ctrl.send(
"\x53\xf4\x42\x03\x00\x00")
309 print(
"Connection activated")
314 rawdata = intr.recv(128)
315 except BluetoothError
as s:
316 print(
"Got Bluetooth error %s. Disconnecting." % s)
318 if len(rawdata) == 0:
319 print(
"Joystick shut down the connection, battery may be discharged.")
321 if not rosgraph.masterapi.is_online():
322 print(
"The roscore or node shutdown, ps3joy shutting down.")
325 stepout = self.
step(rawdata)
327 lastvalidtime = curtime
329 lastactivitytime = curtime
331 print(
"Joystick inactive for %.0f seconds. Disconnecting to save " 334 if curtime - lastvalidtime >= 0.1:
337 if curtime - lastvalidtime >= 5:
339 print(
"No valid data for 5 seconds. Disconnecting. This should not happen, please report it.")
352 18:
"USB Connection",
354 22:
"Bluetooth Connection"}
363 self.
diag_pub = rospy.Publisher(
'/diagnostics', DiagnosticArray)
367 STATE_INDEX_CHARGING = 0
368 STATE_INDEX_BATTERY = 1
369 STATE_INDEX_CONNECTION = 2
372 curr_time = rospy.get_rostime()
378 diag = DiagnosticArray()
379 diag.header.stamp = curr_time
381 stat = DiagnosticStatus(name=
"Battery", level=DiagnosticStatus.OK, message=
"OK")
383 battery_state_code = state[STATE_INDEX_BATTERY]
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)
396 stat = DiagnosticStatus(name=
'ps3joy'": Connection Type", level=DiagnosticStatus.OK, message=
"OK")
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)
405 stat = DiagnosticStatus(name=
'ps3joy'": Charging State", level=DiagnosticStatus.OK, message=
"OK")
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)
419 Exception.__init__(self)
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")
438 sock = BluetoothSocket(L2CAP)
442 sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
449 sock.bind((
"", port))
450 except Exception
as e:
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)
466 self.
listen(intr_sock, ctrl_sock)
471 self.
listen(intr_sock, ctrl_sock)
475 while not rospy.is_shutdown():
476 print(
"Waiting for connection. Disconnect your PS3 joystick from USB and press the pairing button.")
478 intr_sock.settimeout(5)
479 ctrl_sock.settimeout(1)
482 (intr, (idev, iport)) = intr_sock.accept()
484 except Exception
as e:
485 if str(e) ==
'timed out':
492 (ctrl, (cdev, cport)) = ctrl_sock.accept()
493 except Exception
as e:
494 print(
"Got interrupt connection without control connection. Giving up on it.",
500 print(
"Connection terminated.")
503 print(
"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.")
515 except Exception
as e:
516 traceback.print_exc()
517 print(
"Caught exception: %s" % str(e), file=sys.stderr)
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.")
531 if not arg.startswith(prefix):
533 if not arg.startswith(prefix+
"="):
534 print(
"Expected '=' after "+prefix)
540 if __name__ ==
"__main__":
543 inactivity_timeout = float(1e3000)
544 disable_bluetoothd =
True 546 for arg
in sys.argv[1:]:
550 str_value = arg[len(inactivity_timout_string)+1:]
552 inactivity_timeout = float(str_value)
553 if inactivity_timeout < 0:
554 print(
"Inactivity timeout must be positive.")
558 print(
"Error parsing inactivity timeout: "+str_value)
561 elif arg == no_disable_bluetoothd_string:
562 disable_bluetoothd =
False 564 str_value = arg[len(redirect_output_string)+1:]
566 print(
"Redirecting output to:", str_value)
567 sys.stdout = open(str_value,
"a", 1)
569 print(
"Error opening file to redirect output:", str_value)
571 sys.stderr = sys.stdout
573 print(
"Ignoring parameter: '%s'" % arg)
577 print(
"ps3joy.py must be run as root.", file=sys.stderr)
579 if disable_bluetoothd:
580 os.system(
"/etc/init.d/bluetooth stop > /dev/null 2>&1")
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)
587 if inactivity_timeout == float(1e3000):
588 print(
"No inactivity timeout was set. (Run with --help for details.)")
590 print(
"Inactivity timeout set to %.0f seconds." % inactivity_timeout)
592 cm.listen_bluetooth()
594 if disable_bluetoothd:
595 os.system(
"/etc/init.d/bluetooth start > /dev/null 2>&1")
597 errorcode = e.errorcode
598 except KeyboardInterrupt:
599 print(
"\nCTRL+C detected. Exiting.")
600 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)
def prepare_socket(self, sock, port)
def __init__(self, errorcode)