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


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