akaiLPD8.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # joystick input driver for akaiLPD8 input device
00004 # http://www.amazon.com/Akai-Professional-LPD8-Ultra-Portable-Controller/dp/B002M8EEW8
00005 # When you use the button, set 'PAD' mode by the left side button.
00006 
00007 import roslib
00008 import rospy
00009 
00010 import pygame
00011 import pygame.midi
00012 
00013 import sys
00014 
00015 from sensor_msgs.msg import *
00016 
00017 
00018 BUTTON_INDICES = [40, 41, 42, 43,
00019                   36, 37, 38, 39]
00020 AXIS_INDICES = [1, 2, 3, 4,
00021                 5, 6, 7, 8]
00022 
00023 
00024 def main():
00025    rospy.init_node('akailpd8_joy')
00026    pub = rospy.Publisher('/akailpd8/joy', Joy, latch=True)
00027 
00028    pygame.midi.init()
00029    devices = pygame.midi.get_count()
00030    if devices < 1:
00031       rospy.logerr("No MIDI devices detected")
00032       exit(-1)
00033    rospy.loginfo("Found %d MIDI devices" % devices)
00034 
00035    if len(sys.argv) > 1:
00036       input_dev = int(sys.argv[1])
00037    else:
00038       rospy.loginfo("no input device supplied. will try to use default device.")
00039       input_dev = pygame.midi.get_default_input_id()
00040       if input_dev == -1:
00041          rospy.logerr("No default MIDI input device")
00042          exit(-1)
00043    rospy.loginfo("Using input device %d" % input_dev)
00044 
00045    controller = pygame.midi.Input(input_dev)
00046    rospy.loginfo("Opened it")
00047 
00048    m = Joy()
00049    m.axes = [ 0 ] * len(AXIS_INDICES)
00050    m.buttons = [ 0 ] * len(BUTTON_INDICES)
00051 
00052    p = False
00053 
00054    while not rospy.is_shutdown():
00055       m.header.stamp = rospy.Time.now()
00056       
00057       # count the number of events that are coalesced together
00058       c = 0
00059       while controller.poll():
00060          c += 1
00061          data = controller.read(1)
00062          rospy.loginfo("%s" % data)
00063          # loop through events received
00064          for event in data:
00065             control = event[0]
00066             timestamp = event[1]
00067             button_index = control[1]
00068 
00069             for bi, i in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
00070                if button_index == bi:
00071                   if control[0] == 144:
00072                      m.buttons[i] = 1
00073                      p = True
00074                   elif control[0] == 128:
00075                      m.buttons[i] = 0
00076                      p = True
00077             for bi, i in zip(AXIS_INDICES, range(len(AXIS_INDICES))):
00078                if button_index == bi:
00079                   m.axes[i] = control[2] / 127.0
00080                   p = True
00081       if p:
00082          pub.publish(m)
00083          p = False
00084 
00085       rospy.sleep(0.01) # 100hz max
00086                   
00087 
00088 
00089 if __name__ == '__main__':
00090    try:
00091       main()
00092    except rospy.ROSInterruptException:
00093       pass


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