midi_config_player.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import pygame
3 import pygame.midi
4 import select
5 import sys
6 import yaml
7 import rospy
8 import roslib
9 
10 try:
11  from sensor_msgs.msg import Joy, JoyFeedbackArray
12  from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
13 except:
14  roslib.load_manifest('jsk_teleop_joy')
15  from sensor_msgs.msg import Joy, JoyFeedbackArray
16  from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
17 
18 def feedback_array_cb(out_controller, config, msg_arr):
19  global joy
20  output_config = config["output"]
21  for msg in msg_arr.array:
22  if len(output_config) <= msg.id:
23  rospy.logerr("%d is out of output configuration (%d configurations)" % (msg.id, len(output_config)))
24  return
25  the_config = output_config[msg.id]
26  command = the_config[0]
27  channel = the_config[1]
28  val = int(msg.intensity * 127)
29  if val < 0:
30  val = 0
31  elif val > 127:
32  val = 127
33  if the_config[2]:
34  out_controller.write_short(command | channel, val, 0)
35  else:
36  param1 = the_config[3]
37  out_controller.write_short(command | channel, param1, val)
38  try:
39  index = config["analogs"].index((MIDICommand.CONTINUOUS_CONTROLLER,param1))
40  joy.axes[index] = msg.intensity
41  except:
42  pass
43 
44 def main():
45  global joy
46  pygame.midi.init()
47  rospy.init_node('midi_joy')
48  # parse the arg
49  argv = rospy.myargv()
50  if len(argv) == 0:
51  rospy.logfatal("You need to specify config yaml file")
52  sys.exit(1)
53  config_file = argv[1]
54  joy_pub = rospy.Publisher("/joy", Joy, queue_size=10)
55  autorepeat_rate = rospy.get_param("~autorepeat_rate", 0)
56  if autorepeat_rate == 0:
57  r = rospy.Rate(1000)
58  else:
59  r = rospy.Rate(autorepeat_rate)
60  with open(config_file, "r") as f:
61  config = yaml.load(f)
62  # open the device
63  controller = openMIDIInputByName(config["device_name"])
64 
65  joy = Joy()
66  joy.axes = [0.0] * len(config["analogs"])
67  # automatically mapping to buttons from axes if it has NOTE_OFF or NOTE_ON MIDI commands
68  button_configs = [c for c in config["analogs"]
69  if c[0] == MIDICommand.NOTE_ON or c[0] == MIDICommand.NOTE_OFF]
70  if config.has_key("output"):
71  out_controller = openMIDIOutputByName(config["device_name"])
72  s = rospy.Subscriber("~set_feedback", JoyFeedbackArray, lambda msg: feedback_array_cb(out_controller, config, msg))
73  joy.buttons = [0] * len(button_configs)
74  while not rospy.is_shutdown():
75  joy.header.stamp = rospy.Time.now()
76  p = False
77  while controller.poll():
78  data = controller.read(1)
79  for elem_set in data:
80  p = True
81  (command, ind, val) = MIDIParse(elem_set)
82  try:
83  index = config["analogs"].index((command, ind))
84  joy.axes[index] = val
85  if command == MIDICommand.NOTE_ON or command == MIDICommand.NOTE_OFF:
86  button_index = button_configs.index((command, ind))
87  if val == 0.0:
88  joy.buttons[button_index] = 0
89  else:
90  joy.buttons[button_index] = 1
91  except:
92  rospy.logwarn("unknown MIDI message: (%d, %d, %f)" % (command, ind, val))
93  if (autorepeat_rate != 0) or p:
94  joy_pub.publish(joy)
95  r.sleep()
96 if __name__ == '__main__':
97  main()
98 
def MIDIParse(message)
Definition: midi_util.py:7
def openMIDIInputByName(device_name)
Definition: midi_util.py:82
def openMIDIOutputByName(device_name)
Definition: midi_util.py:85
def feedback_array_cb(out_controller, config, msg_arr)


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