nanokontrol_joy.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 
17 BUTTON_INDICES = [58, 59,
18  46, 60, 61, 62,
19  43, 44, 42, 41, 45,
20  32, 33, 34, 35, 36, 37, 38, 39,
21  48, 49, 50, 51, 52, 53, 54, 55,
22  64, 65, 66, 67, 68, 69, 70, 71]
23 AXIS_INDICES = [16, 17, 18, 19, 20, 21, 22, 23,
24  0, 1, 2, 3, 4, 5, 6, 7]
25 
26 
27 def main():
28  rospy.init_node('nanokontrol_joy')
29  pub = rospy.Publisher('/nanokontrol/joy', Joy, latch=True)
30 
31  pygame.midi.init()
32  devices = pygame.midi.get_count()
33  if devices < 1:
34  rospy.logerr("No MIDI devices detected")
35  exit(-1)
36  rospy.loginfo("Found %d MIDI devices" % devices)
37 
38  if len(sys.argv) > 1:
39  input_dev = int(sys.argv[1])
40  else:
41  rospy.loginfo("no input device supplied. will try to use default device.")
42  input_dev = pygame.midi.get_default_input_id()
43  if input_dev == -1:
44  rospy.logerr("No default MIDI input device")
45  exit(-1)
46  rospy.loginfo("Using input device %d" % input_dev)
47 
48  controller = pygame.midi.Input(input_dev)
49  rospy.loginfo("Opened it")
50 
51  m = Joy()
52  m.axes = [ 0 ] * len(AXIS_INDICES)
53  m.buttons = [ 0 ] * len(BUTTON_INDICES)
54 
55  p = False
56 
57  while not rospy.is_shutdown():
58  m.header.stamp = rospy.Time.now()
59 
60  # count the number of events that are coalesced together
61  c = 0
62  while controller.poll():
63  c += 1
64  data = controller.read(1)
65  rospy.loginfo("%s" % data)
66  # loop through events received
67  for event in data:
68  control = event[0]
69  timestamp = event[1]
70  button_index = control[1]
71 
72  for bi, i in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
73  if button_index == bi:
74  if control[2] == 127:
75  m.buttons[i] = 1
76  else:
77  m.buttons[i] = 0
78  p = True
79  for bi, i in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
80  if button_index == bi:
81  m.axes[i] = control[2] / 127.0
82  p = True
83  if p:
84  pub.publish(m)
85  p = False
86 
87  rospy.sleep(0.01) # 100hz max
88 
89 
90 
91 if __name__ == '__main__':
92  try:
93  main()
94  except rospy.ROSInterruptException:
95  pass


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