17 BUTTON_INDICES = [37, 39, 41, 43, 45, 47, 49, 51,
18 36, 38, 40, 42, 44, 46, 48, 50]
23 rospy.init_node(
'nanopad_joy')
24 pub = rospy.Publisher(
'/nanopad/joy', Joy, latch=
True)
27 devices = pygame.midi.get_count()
29 rospy.logerr(
"No MIDI devices detected")
31 rospy.loginfo(
"Found %d MIDI devices" % devices)
34 input_dev = int(sys.argv[1])
36 rospy.loginfo(
"no input device supplied. will try to use default device.")
37 input_dev = pygame.midi.get_default_input_id()
39 rospy.logerr(
"No default MIDI input device")
41 rospy.loginfo(
"Using input device %d" % input_dev)
43 controller = pygame.midi.Input(input_dev)
44 rospy.loginfo(
"Opened it")
47 m.axes = [ 0 ] * len(AXIS_INDICES)
48 m.buttons = [ 0 ] * len(BUTTON_INDICES)
52 while not rospy.is_shutdown():
53 m.header.stamp = rospy.Time.now()
57 while controller.poll():
59 data = controller.read(1)
60 rospy.loginfo(
"%s" % data)
65 button_index = control[1]
67 for bi, i
in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
68 if button_index == bi:
71 elif control[0] == 128:
74 for bi, i
in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
75 if button_index == bi:
76 m.axes[i] = control[2] / 127.0
86 if __name__ ==
'__main__':
89 except rospy.ROSInterruptException: