lanchpad_mini_joy.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # joystick input driver for Launchpad Mini input device
4 # http://www.amazon.com/Novation-Launchpad-Controller-Performing-Producing/dp/B00F9SWK9M
5 
6 import roslib
7 import rospy
8 
9 import pygame
10 import pygame.midi
11 
12 import sys
13 
14 from sensor_msgs.msg import *
15 
16 
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
27  ]
28 
29 AXIS_INDICES = []
30 COLOR_R = 3
31 COLOR_G = 3
32 
33 def main():
34  rospy.init_node('launchpad_mini_joy')
35  pub = rospy.Publisher('/launchpad_mini/joy', Joy, latch=True)
36 
37  pygame.midi.init()
38  devices = pygame.midi.get_count()
39  if devices < 1:
40  rospy.logerr("No MIDI devices detected")
41  exit(-1)
42  rospy.loginfo("Found %d MIDI devices" % devices)
43 
44  if len(sys.argv) > 1:
45  input_dev = int(sys.argv[1])
46  else:
47  rospy.loginfo("no input device supplied. will try to use default device.")
48  input_dev = pygame.midi.get_default_input_id()
49  if input_dev == -1:
50  rospy.logerr("No default MIDI input device")
51  exit(-1)
52 
53  if len(sys.argv) > 2:
54  output_dev = int(sys.argv[2])
55  else:
56  rospy.loginfo("no output device supplied. will try to use default device.")
57  output_dev = pygame.midi.get_default_output_id()
58 
59  if output_dev == -1:
60  rospy.logerr("No default MIDI output device")
61  exit(-1)
62 
63  rospy.loginfo("Using input device %d" % input_dev)
64  rospy.loginfo("Using output device %d" % output_dev)
65 
66  controller = pygame.midi.Input(input_dev)
67  midi_output = pygame.midi.Output(output_dev)
68  rospy.loginfo("Opened it")
69 
70  m = Joy()
71  m.axes = [ 0 ] * len(AXIS_INDICES)
72  m.buttons = [ 0 ] * len(BUTTON_INDICES)
73 
74  p = False
75 
76  while not rospy.is_shutdown():
77  m.header.stamp = rospy.Time.now()
78 
79  # count the number of events that are coalesced together
80  c = 0
81  while controller.poll():
82  c += 1
83  data = controller.read(1)
84  rospy.loginfo("%s" % data)
85  # loop through events received
86  for event in data:
87  control = event[0]
88  timestamp = event[1]
89  button_type = control[0]
90  button_index = control[1]
91 
92  for bi, i in zip(BUTTON_INDICES, range(len(BUTTON_INDICES))):
93  if button_index == bi:
94  #duplicated number
95  if i == 64 and button_type != 176:
96  continue
97  if i == 78 and button_type != 144:
98  continue
99 
100  if control[2] == 127:
101  m.buttons[i] = 1
102  midi_output.write([[[button_type ,button_index , COLOR_G * 4 + COLOR_R ], timestamp]])
103  else:
104  m.buttons[i] = 0
105  midi_output.write([[[button_type ,button_index , 0], timestamp]])
106  p = True
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
110  p = True
111  if p:
112  pub.publish(m)
113  p = False
114 
115  rospy.sleep(0.01) # 100hz max
116 
117 
118 
119 if __name__ == '__main__':
120  try:
121  main()
122  except rospy.ROSInterruptException:
123  pass


jsk_teleop_joy
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:52:11