akaiLPD8.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # joystick input driver for akaiLPD8 input device
4 # http://www.amazon.com/Akai-Professional-LPD8-Ultra-Portable-Controller/dp/B002M8EEW8
5 # When you use the button, set 'PAD' mode by the left side button.
6 
7 import roslib
8 import rospy
9 
10 import pygame
11 import pygame.midi
12 
13 import sys
14 
15 from sensor_msgs.msg import *
16 
17 
18 BUTTON_INDICES = [40, 41, 42, 43,
19  36, 37, 38, 39]
20 AXIS_INDICES = [1, 2, 3, 4,
21  5, 6, 7, 8]
22 
23 
24 def main():
25  rospy.init_node('akailpd8_joy')
26  pub = rospy.Publisher('/akailpd8/joy', Joy, latch=True)
27 
28  pygame.midi.init()
29  devices = pygame.midi.get_count()
30  if devices < 1:
31  rospy.logerr("No MIDI devices detected")
32  exit(-1)
33  rospy.loginfo("Found %d MIDI devices" % devices)
34 
35  if len(sys.argv) > 1:
36  input_dev = int(sys.argv[1])
37  else:
38  rospy.loginfo("no input device supplied. will try to use default device.")
39  input_dev = pygame.midi.get_default_input_id()
40  if input_dev == -1:
41  rospy.logerr("No default MIDI input device")
42  exit(-1)
43  rospy.loginfo("Using input device %d" % input_dev)
44 
45  controller = pygame.midi.Input(input_dev)
46  rospy.loginfo("Opened it")
47 
48  m = Joy()
49  m.axes = [ 0 ] * len(AXIS_INDICES)
50  m.buttons = [ 0 ] * len(BUTTON_INDICES)
51 
52  p = False
53 
54  while not rospy.is_shutdown():
55  m.header.stamp = rospy.Time.now()
56 
57  # count the number of events that are coalesced together
58  c = 0
59  while controller.poll():
60  c += 1
61  data = controller.read(1)
62  rospy.loginfo("%s" % data)
63  # loop through events received
64  for event in data:
65  control = event[0]
66  timestamp = event[1]
67  button_index = control[1]
68 
69  for bi, i in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
70  if button_index == bi:
71  if control[0] == 144:
72  m.buttons[i] = 1
73  p = True
74  elif control[0] == 128:
75  m.buttons[i] = 0
76  p = True
77  for bi, i in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
78  if button_index == bi:
79  m.axes[i] = control[2] / 127.0
80  p = True
81  if p:
82  pub.publish(m)
83  p = False
84 
85  rospy.sleep(0.01) # 100hz max
86 
87 
88 
89 if __name__ == '__main__':
90  try:
91  main()
92  except rospy.ROSInterruptException:
93  pass
def main()
Definition: akaiLPD8.py:24


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:52:11