00001
00002
00003
00004
00005
00006
00007 import roslib; roslib.load_manifest('korg_nanokontrol')
00008 import rospy
00009
00010 import pygame
00011 import pygame.midi
00012
00013 import sys
00014
00015 from sensor_msgs.msg import *
00016
00017 control_axes = [{
00018
00019 2: 0, 3: 1, 4: 2, 5: 3, 6: 4, 8: 5, 9: 6, 12: 7, 13: 8,
00020
00021 14: 9, 15: 10, 16: 11, 17: 12, 18: 13, 19: 14, 20: 15, 21: 16, 22: 17,
00022 },{
00023
00024 42: 0, 43: 1, 50: 2, 51: 3, 52: 4, 53: 5, 54: 6, 55: 7, 56: 8,
00025
00026 57: 9, 58: 10, 59: 11, 60: 12, 61: 13, 62: 14, 63: 15, 65: 16, 66: 17,
00027 },{
00028
00029 85: 0, 86: 1, 87: 2, 88: 3, 89: 4, 90: 5, 91: 6, 92: 7, 93: 8,
00030
00031 94: 9, 95: 10, 96: 11, 97: 12, 102: 13, 103: 14, 104: 15, 105: 16, 106: 17,
00032 },{
00033
00034 7: 0, 263: 1, 519: 2, 775: 3, 1031: 4, 1287: 5, 1543: 6, 1799: 7, 2055: 8,
00035
00036 10: 9, 266: 10, 522: 11, 778: 12, 1034: 13, 1290: 14, 1546: 15, 1802: 16,
00037 2058: 17,
00038 }]
00039
00040 control_buttons = [[
00041
00042
00043 23, 33, 24, 34, 25, 35, 26, 36, 27, 37, 28, 38, 29, 39, 30, 40, 31, 41,
00044
00045 47, 45, 48, 49, 46, 44
00046 ],[
00047
00048
00049 67, 76, 68, 77, 69, 78, 70, 79, 71, 80, 72, 81, 73, 82, 74, 83, 75, 84,
00050
00051 47, 45, 48, 49, 46, 44
00052 ],[
00053
00054
00055 107, 116, 108, 117, 109, 118, 110, 119, 111, 120, 112, 121, 113, 122, 114, 123, 115, 124,
00056
00057 47, 45, 48, 49, 46, 44
00058 ],[
00059
00060
00061 16, 17, 272, 273, 528, 529, 784, 785, 1040, 1041, 1296, 1297, 1552, 1553, 1808, 1809, 2064, 2065,
00062
00063 47, 45, 48, 49, 46, 44
00064 ]]
00065
00066 def main():
00067 pygame.midi.init()
00068 devices = pygame.midi.get_count()
00069 if devices < 1:
00070 print "No MIDI devices detected"
00071 exit(-1)
00072 print "Found %d MIDI devices" % devices
00073
00074 if len(sys.argv) > 1:
00075 input_dev = int(sys.argv[1])
00076 else:
00077 input_dev = pygame.midi.get_default_input_id()
00078 if input_dev == -1:
00079 print "No default MIDI input device"
00080 exit(-1)
00081 print "Using input device %d" % input_dev
00082
00083 controller = pygame.midi.Input(input_dev)
00084
00085 rospy.init_node('kontrol')
00086 pub = rospy.Publisher('joy', Joy, latch=True)
00087
00088 m = Joy()
00089 m.axes = [ 0 ] * 18
00090 m.buttons = [ 0 ] * 25
00091 mode = None
00092
00093 p = False
00094
00095 while not rospy.is_shutdown():
00096 m.header.stamp = rospy.Time.now()
00097
00098 c = 0
00099 while controller.poll():
00100 c += 1
00101 data = controller.read(1)
00102
00103
00104 for event in data:
00105 control = event[0]
00106 timestamp = event[1]
00107
00108
00109 if (control[0] & 0xF0) == 176:
00110 control_id = control[1] | ((control[0] & 0x0F) << 8)
00111
00112
00113 if mode is None:
00114 candidate = None
00115 for index, control_axis in enumerate(control_axes):
00116 if control_id in control_axis:
00117 if candidate is not None:
00118 candidate = None
00119 break
00120 candidate = index
00121 for index, control_button in enumerate(control_buttons):
00122 if control_id in control_button:
00123 if candidate is not None:
00124 candidate = None
00125 break
00126 candidate = index
00127 mode = candidate
00128 if mode is None:
00129 print 'skipped because mode is yet unknown'
00130 continue
00131
00132 if control_id in control_axes[mode]:
00133 control_val = float(control[2] - 63) / 63.0
00134 if control_val < -1.0:
00135 control_val = -1.0
00136 if control_val > 1.0:
00137 control_val = 1.0
00138
00139 axis = control_axes[mode][control_id]
00140 m.axes[axis] = control_val
00141 p = True
00142
00143 if control_id in control_buttons[mode]:
00144 button = control_buttons[mode].index(control_id)
00145 if control[2] != 0:
00146 m.buttons[button] = 1
00147 else:
00148 m.buttons[button] = 0
00149 p = True
00150
00151 elif control[0] == 79:
00152 mode = control[1]
00153 m.buttons[24] = mode
00154 p = True
00155
00156 if p:
00157 pub.publish(m)
00158 p = False
00159
00160 rospy.sleep(0.1)
00161
00162
00163
00164 if __name__ == '__main__':
00165 try:
00166 main()
00167 except rospy.ROSInterruptException: pass