vestax_spin2.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # joystick input driver for nanoKontrol input device
4 # http://www.amazon.co.jp/KORG-USB-MIDI-%E3%82%B3%E3%83%B3%E3%83%88%E3%83%AD%E3%83%BC%E3%83%A9%E3%83%BC-NANO-KONTROL2/dp/B004M8UZS8
5 
6 import roslib;
7 import rospy
8 
9 import pygame
10 import pygame.midi
11 
12 import sys
13 
14 from sensor_msgs.msg import *
15 
16 BUTTON_INDICES0 = range(32, 38)
17 BUTTON_INDICES1 = [46, 47, 48, 49, 42, 43, 44, 98, 99, 100, 101, 102, 103, 35, 36, 37, 34, 104, 45, 50, 32, 33]
18 SCRATCH_INDICES = [16, 17]
19 AXIS_INDICES0 = [16]
20 AXIS_INDICES1 = [28, 27, 17, 18, 19, 20, 26, 16, 29]
21 AXIS_INDICES2 = [22, 17, 28, 19, 18, 21, 27, 20, 23]
22 
23 
24 
25 def main():
26  pygame.midi.init()
27  devices = pygame.midi.get_count()
28  if devices < 1:
29  print("No MIDI devices detected")
30  exit(-1)
31  print("Found %d MIDI devices" % devices)
32 
33  if len(sys.argv) > 1:
34  input_dev = int(sys.argv[1])
35  else:
36  for i in range(devices):
37  info = pygame.midi.get_device_info(i)
38  if 'Vestax Spin 2 MIDI' in info[1]:
39  if info[2] == 1: # is input device?
40  input_dev = i
41  break
42  if not input_dev:
43  print("No MIDI device")
44  exit(-1)
45  print("Using input device %d" % input_dev)
46 
47  controller = pygame.midi.Input(input_dev)
48  print("Opened it")
49 
50  rospy.init_node('kontrol')
51  pub = rospy.Publisher('/joy_pad', Joy, latch=True)
52 
53  m = Joy()
54  m.axes = [ 0 ] * (2 + len(AXIS_INDICES0) + len(AXIS_INDICES1) + len(AXIS_INDICES2))
55  m.buttons = [ 0 ] * (len(BUTTON_INDICES0) + 2 * len(BUTTON_INDICES1))
56  mode = None
57 
58  p = False
59 
60  while not rospy.is_shutdown():
61  m.header.stamp = rospy.Time.now()
62 
63  # count the number of events that are coalesced together
64  c = 0
65  while controller.poll():
66  c += 1
67  data = controller.read(1)
68  print(data)
69  # loop through events received
70  for event in data:
71  control = event[0]
72  timestamp = event[1]
73  # look for continuous controller commands
74 
75  # button
76  if control[0] in [144,145,146]:
77  player = control[0] - 144
78  button_index = control[1]
79  pressed = True if control[2] == 127 else False
80  if player == 2: # common
81  for bi, i in zip(BUTTON_INDICES0, range(len(BUTTON_INDICES0))):
82  if button_index == bi:
83  if pressed:
84  m.buttons[i] = 1
85  else:
86  m.buttons[i] = 0
87  p = True
88  else:
89  for bi, i in zip(BUTTON_INDICES1, range(len(BUTTON_INDICES1))):
90  if button_index == bi:
91  offset = player * len(BUTTON_INDICES1) + len(BUTTON_INDICES0)
92  if pressed:
93  m.buttons[i + offset] = 1
94  else:
95  m.buttons[i + offset] = 0
96  p = True
97  # slider
98  elif control[0] in [176, 177, 180]:
99  player = control[0] - 176
100  axis_index = control[1]
101 
102  if player == 4: # common
103  for bi, i in zip(AXIS_INDICES0, range(len(AXIS_INDICES0))):
104  if axis_index == bi:
105  offset = len(SCRATCH_INDICES)
106  m.axes[i + offset] = control[2] / 127.0
107  p = True
108  elif player == 0:
109  for bi, i in zip(AXIS_INDICES1, range(len(AXIS_INDICES1))):
110  if axis_index == bi:
111  offset = len(SCRATCH_INDICES) + len(AXIS_INDICES0)
112  m.axes[i + offset] = control[2] / 127.0
113  p = True
114  elif player == 1:
115  for bi, i in zip(AXIS_INDICES2, range(len(AXIS_INDICES2))):
116  if axis_index == bi:
117  offset = len(SCRATCH_INDICES) + len(AXIS_INDICES0) + len(AXIS_INDICES1)
118  m.axes[i + offset] = control[2] / 127.0
119  p = True
120  # scratch
121  elif control[0] == 178:
122  for s, i in zip(SCRATCH_INDICES, range(len(SCRATCH_INDICES))):
123  if control[1] == s:
124  if control[2] > 64:
125  m.axes[i] = (control[2] - 65) / 15.0
126  else:
127  m.axes[i] = (control[2] - 63) / 15.0
128  p = True
129  else:
130  continue
131  if p:
132  pub.publish(m)
133  p = False
134 
135  rospy.sleep(0.01) # 100hz max
136 
137 
138 
139 if __name__ == '__main__':
140  try:
141  main()
142  except rospy.ROSInterruptException: pass


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