17 BUTTON_INDICES = [0, 1, 2, 3, 4, 5, 6, 7,
18 16, 17, 18, 19, 20, 21, 22, 23,
19 32, 33, 34, 35, 36, 37, 38, 39,
20 48, 49, 50, 51, 52, 53, 54, 55,
21 64, 65, 66, 67, 68, 69, 70, 71,
22 80, 81, 82, 83, 84, 85, 86, 87,
23 96, 97, 98, 99, 100, 101, 102, 103,
24 112, 113, 114, 115, 116, 117, 118, 119,
25 104, 105, 106, 107, 108, 109, 110, 111,
26 8, 24, 40, 56, 72, 88, 104, 120
34 rospy.init_node(
'launchpad_mini_joy')
35 pub = rospy.Publisher(
'/launchpad_mini/joy', Joy, latch=
True)
38 devices = pygame.midi.get_count()
40 rospy.logerr(
"No MIDI devices detected")
42 rospy.loginfo(
"Found %d MIDI devices" % devices)
45 input_dev = int(sys.argv[1])
47 rospy.loginfo(
"no input device supplied. will try to use default device.")
48 input_dev = pygame.midi.get_default_input_id()
50 rospy.logerr(
"No default MIDI input device")
54 output_dev = int(sys.argv[2])
56 rospy.loginfo(
"no output device supplied. will try to use default device.")
57 output_dev = pygame.midi.get_default_output_id()
60 rospy.logerr(
"No default MIDI output device")
63 rospy.loginfo(
"Using input device %d" % input_dev)
64 rospy.loginfo(
"Using output device %d" % output_dev)
66 controller = pygame.midi.Input(input_dev)
67 midi_output = pygame.midi.Output(output_dev)
68 rospy.loginfo(
"Opened it")
71 m.axes = [ 0 ] * len(AXIS_INDICES)
72 m.buttons = [ 0 ] * len(BUTTON_INDICES)
76 while not rospy.is_shutdown():
77 m.header.stamp = rospy.Time.now()
81 while controller.poll():
83 data = controller.read(1)
84 rospy.loginfo(
"%s" % data)
89 button_type = control[0]
90 button_index = control[1]
92 for bi, i
in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
93 if button_index == bi:
95 if i == 64
and button_type != 176:
97 if i == 78
and button_type != 144:
100 if control[2] == 127:
102 midi_output.write([[[button_type ,button_index , COLOR_G * 4 + COLOR_R ], timestamp]])
105 midi_output.write([[[button_type ,button_index , 0], timestamp]])
107 for bi, i
in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
108 if button_index == bi:
109 m.axes[i] = control[2] / 127.0
119 if __name__ ==
'__main__':
122 except rospy.ROSInterruptException: