18 BUTTON_INDICES = [40, 41, 42, 43,
20 AXIS_INDICES = [1, 2, 3, 4,
25 rospy.init_node(
'akailpd8_joy')
26 pub = rospy.Publisher(
'/akailpd8/joy', Joy, latch=
True)
29 devices = pygame.midi.get_count()
31 rospy.logerr(
"No MIDI devices detected")
33 rospy.loginfo(
"Found %d MIDI devices" % devices)
36 input_dev = int(sys.argv[1])
38 rospy.loginfo(
"no input device supplied. will try to use default device.")
39 input_dev = pygame.midi.get_default_input_id()
41 rospy.logerr(
"No default MIDI input device")
43 rospy.loginfo(
"Using input device %d" % input_dev)
45 controller = pygame.midi.Input(input_dev)
46 rospy.loginfo(
"Opened it")
49 m.axes = [ 0 ] * len(AXIS_INDICES)
50 m.buttons = [ 0 ] * len(BUTTON_INDICES)
54 while not rospy.is_shutdown():
55 m.header.stamp = rospy.Time.now()
59 while controller.poll():
61 data = controller.read(1)
62 rospy.loginfo(
"%s" % data)
67 button_index = control[1]
69 for bi, i
in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
70 if button_index == bi:
74 elif control[0] == 128:
77 for bi, i
in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
78 if button_index == bi:
79 m.axes[i] = control[2] / 127.0
89 if __name__ ==
'__main__':
92 except rospy.ROSInterruptException: