vestax_spin2.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # joystick input driver for nanoKontrol input device
00004 # http://www.amazon.co.jp/KORG-USB-MIDI-%E3%82%B3%E3%83%B3%E3%83%88%E3%83%AD%E3%83%BC%E3%83%A9%E3%83%BC-NANO-KONTROL2/dp/B004M8UZS8
00005 
00006 import roslib;
00007 import rospy
00008 
00009 import pygame
00010 import pygame.midi
00011 
00012 import sys
00013 
00014 from sensor_msgs.msg import *
00015 
00016 BUTTON_INDICES0 = range(32, 38)
00017 BUTTON_INDICES1 = [46, 47, 48, 49, 42, 43, 44, 98, 99, 100, 101, 102, 103, 35, 36, 37, 34, 104, 45, 50, 32, 33]
00018 SCRATCH_INDICES = [16, 17]
00019 AXIS_INDICES0 = [16]
00020 AXIS_INDICES1 = [28, 27, 17, 18, 19, 20, 26, 16, 29]
00021 AXIS_INDICES2 = [22, 17, 28, 19, 18, 21, 27, 20, 23]
00022 
00023 
00024 
00025 def main():
00026    pygame.midi.init()
00027    devices = pygame.midi.get_count()
00028    if devices < 1:
00029       print "No MIDI devices detected"
00030       exit(-1)
00031    print "Found %d MIDI devices" % devices
00032 
00033    if len(sys.argv) > 1:
00034       input_dev = int(sys.argv[1])
00035    else:
00036        for i in range(devices):
00037            info = pygame.midi.get_device_info(i)
00038            if 'Vestax Spin 2 MIDI' in info[1]:
00039                if info[2] == 1: # is input device?
00040                    input_dev = i
00041                    break
00042        if not input_dev:
00043            print "No MIDI device"
00044            exit(-1)
00045    print "Using input device %d" % input_dev
00046 
00047    controller = pygame.midi.Input(input_dev)
00048    print "Opened it"
00049 
00050    rospy.init_node('kontrol')
00051    pub = rospy.Publisher('/joy_pad', Joy, latch=True)
00052 
00053    m = Joy()
00054    m.axes = [ 0 ] * (2 + len(AXIS_INDICES0) + len(AXIS_INDICES1) + len(AXIS_INDICES2))
00055    m.buttons = [ 0 ] * (len(BUTTON_INDICES0) + 2 * len(BUTTON_INDICES1))
00056    mode = None
00057 
00058    p = False
00059 
00060    while not rospy.is_shutdown():
00061       m.header.stamp = rospy.Time.now()
00062 
00063       # count the number of events that are coalesced together
00064       c = 0
00065       while controller.poll():
00066          c += 1
00067          data = controller.read(1)
00068          print data
00069          # loop through events received
00070          for event in data:
00071             control = event[0]
00072             timestamp = event[1]
00073             # look for continuous controller commands
00074 
00075             # button
00076             if control[0] in [144,145,146]:
00077                 player = control[0] - 144
00078                 button_index = control[1]
00079                 pressed = True if control[2] == 127 else False
00080                 if player == 2: # common
00081                     for bi, i in zip(BUTTON_INDICES0, range(len(BUTTON_INDICES0))):
00082                         if button_index == bi:
00083                             if pressed:
00084                                 m.buttons[i] = 1
00085                             else:
00086                                 m.buttons[i] = 0
00087                             p = True
00088                 else:
00089                     for bi, i in zip(BUTTON_INDICES1, range(len(BUTTON_INDICES1))):
00090                         if button_index == bi:
00091                             offset = player * len(BUTTON_INDICES1) + len(BUTTON_INDICES0)
00092                             if pressed:
00093                                 m.buttons[i + offset] = 1
00094                             else:
00095                                 m.buttons[i + offset] = 0
00096                             p = True
00097             # slider
00098             elif control[0] in [176, 177, 180]:
00099                 player = control[0] - 176
00100                 axis_index = control[1]
00101 
00102                 if player == 4: # common
00103                     for bi, i in zip(AXIS_INDICES0, range(len(AXIS_INDICES0))):
00104                         if axis_index == bi:
00105                             offset = len(SCRATCH_INDICES)
00106                             m.axes[i + offset] = control[2] / 127.0
00107                             p = True
00108                 elif player == 0:
00109                     for bi, i in zip(AXIS_INDICES1, range(len(AXIS_INDICES1))):
00110                         if axis_index == bi:
00111                             offset = len(SCRATCH_INDICES) + len(AXIS_INDICES0)
00112                             m.axes[i + offset] = control[2] / 127.0
00113                             p = True
00114                 elif player == 1:
00115                     for bi, i in zip(AXIS_INDICES2, range(len(AXIS_INDICES2))):
00116                         if axis_index == bi:
00117                             offset = len(SCRATCH_INDICES) + len(AXIS_INDICES0) + len(AXIS_INDICES1)
00118                             m.axes[i + offset] = control[2] / 127.0
00119                             p = True
00120             # scratch
00121             elif control[0] == 178:
00122                 for s, i in zip(SCRATCH_INDICES, range(len(SCRATCH_INDICES))):
00123                     if control[1] == s:
00124                         if control[2] > 64:
00125                             m.axes[i] = (control[2] - 65) / 15.0
00126                         else:
00127                             m.axes[i] = (control[2] - 63) / 15.0
00128                         p = True
00129             else:
00130                continue
00131       if p:
00132          pub.publish(m)
00133          p = False
00134 
00135       rospy.sleep(0.01) # 100hz max
00136 
00137 
00138 
00139 if __name__ == '__main__':
00140    try:
00141       main()
00142    except rospy.ROSInterruptException: pass


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Wed Jul 19 2017 02:54:50