Go to the documentation of this file.00001
00002 import pygame
00003 import pygame.midi
00004 import select
00005 import sys
00006 import yaml
00007 import rospy
00008 import roslib
00009
00010 try:
00011 from sensor_msgs.msg import Joy, JoyFeedbackArray
00012 from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
00013 except:
00014 roslib.load_manifest('jsk_teleop_joy')
00015 from sensor_msgs.msg import Joy, JoyFeedbackArray
00016 from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
00017
00018 def feedback_array_cb(out_controller, config, msg_arr):
00019 output_config = config["output"]
00020 for msg in msg_arr.array:
00021 if len(output_config) <= msg.id:
00022 rospy.logerr("%d is out of output configuration (%d configurations)" % (msg.id, len(output_config)))
00023 return
00024 the_config = output_config[msg.id]
00025 command = the_config[0]
00026 channel = the_config[1]
00027 val = int(msg.intensity * 127)
00028 if val < 0:
00029 val = 0
00030 elif val > 127:
00031 val = 127
00032 if the_config[2]:
00033 out_controller.write_short(command | channel, val, 0)
00034 else:
00035 param1 = the_config[3]
00036 out_controller.write_short(command | channel, param1, val)
00037
00038
00039 def main():
00040 pygame.midi.init()
00041 rospy.init_node('midi_joy')
00042
00043 argv = rospy.myargv()
00044 if len(argv) == 0:
00045 rospy.logfatal("You need to specify config yaml file")
00046 sys.exit(1)
00047 config_file = argv[1]
00048 joy_pub = rospy.Publisher("/joy", Joy)
00049 with open(config_file, "r") as f:
00050 config = yaml.load(f)
00051
00052 controller = openMIDIInputByName(config["device_name"])
00053
00054 joy = Joy()
00055 joy.axes = [0.0] * len(config["analogs"])
00056
00057 button_configs = [c for c in config["analogs"]
00058 if c[0] == MIDICommand.NOTE_ON or c[0] == MIDICommand.NOTE_OFF]
00059 if config.has_key("output"):
00060 out_controller = openMIDIOutputByName(config["device_name"])
00061 s = rospy.Subscriber("~set_feedback", JoyFeedbackArray, lambda msg: feedback_array_cb(out_controller, config, msg))
00062 joy.buttons = [0] * len(button_configs)
00063 while not rospy.is_shutdown():
00064 joy.header.stamp = rospy.Time.now()
00065 while controller.poll():
00066 data = controller.read(1)
00067 for elem_set in data:
00068 (command, ind, val) = MIDIParse(elem_set)
00069 try:
00070 index = config["analogs"].index((command, ind))
00071 joy.axes[index] = val
00072 if command == MIDICommand.NOTE_ON or command == MIDICommand.NOTE_OFF:
00073 button_index = button_configs.index((command, ind))
00074 if val == 0.0:
00075 joy.buttons[button_index] = 0
00076 else:
00077 joy.buttons[button_index] = 1
00078 except:
00079 rospy.logwarn("unknown MIDI message: (%d, %d, %f)" % (command, ind, val))
00080 joy_pub.publish(joy)
00081 rospy.sleep(1.0 / 100.0)
00082 if __name__ == '__main__':
00083 main()
00084