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]
29 rospy.init_node(
'nanopad2_joy')
30 pub = rospy.Publisher(
'/nanopad2/joy', Joy, latch=
True)
33 devices = pygame.midi.get_count()
35 rospy.logerr(
"No MIDI devices detected")
37 rospy.loginfo(
"Found %d MIDI devices" % devices)
40 input_dev = int(sys.argv[1])
42 rospy.loginfo(
"no input device supplied. will try to use default device.")
43 input_dev = pygame.midi.get_default_input_id()
45 rospy.logerr(
"No default MIDI input device")
47 rospy.loginfo(
"Using input device %d" % input_dev)
49 controller = pygame.midi.Input(input_dev)
50 rospy.loginfo(
"Opened it")
53 m.axes = [ 0 ] * len(AXIS_INDICES)
54 m.buttons = [ 0 ] * len(BUTTON_INDICES)
58 while not rospy.is_shutdown():
59 m.header.stamp = rospy.Time.now()
63 while controller.poll():
65 data = controller.read(1)
66 rospy.loginfo(
"%s" % data)
71 button_index = control[1]
73 for bi, i
in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
74 if button_index == bi:
77 elif control[0] == 128:
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
92 if __name__ ==
'__main__':
95 except rospy.ROSInterruptException: