12 from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
14 roslib.load_manifest(
'jsk_teleop_joy')
16 from jsk_teleop_joy.midi_util import MIDIParse, MIDICommand, MIDIException, openMIDIInputByName, openMIDIOutputByName
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)))
25 the_config = output_config[msg.id]
26 command = the_config[0]
27 channel = the_config[1]
28 val = int(msg.intensity * 127)
34 out_controller.write_short(command | channel, val, 0)
36 param1 = the_config[3]
37 out_controller.write_short(command | channel, param1, val)
39 index = config[
"analogs"].index((MIDICommand.CONTINUOUS_CONTROLLER,param1))
40 joy.axes[index] = msg.intensity
47 rospy.init_node(
'midi_joy')
51 rospy.logfatal(
"You need to specify config yaml file")
54 joy_pub = rospy.Publisher(
"/joy", Joy, queue_size=10)
55 autorepeat_rate = rospy.get_param(
"~autorepeat_rate", 0)
56 if autorepeat_rate == 0:
59 r = rospy.Rate(autorepeat_rate)
60 with open(config_file,
"r") as f: 66 joy.axes = [0.0] * len(config[
"analogs"])
68 button_configs = [c
for c
in config[
"analogs"]
69 if c[0] == MIDICommand.NOTE_ON
or c[0] == MIDICommand.NOTE_OFF]
70 if "output" in config:
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()
77 while controller.poll():
78 data = controller.read(1)
83 index = config[
"analogs"].index((command, ind))
85 if command == MIDICommand.NOTE_ON
or command == MIDICommand.NOTE_OFF:
86 button_index = button_configs.index((command, ind))
88 joy.buttons[button_index] = 0
90 joy.buttons[button_index] = 1
92 rospy.logwarn(
"unknown MIDI message: (%d, %d, %f)" % (command, ind, val))
93 if (autorepeat_rate != 0)
or p:
96 if __name__ ==
'__main__':
def openMIDIInputByName(device_name)
def openMIDIOutputByName(device_name)
def feedback_array_cb(out_controller, config, msg_arr)