7 roslib.load_manifest(
'jsk_teleop_joy')
9 from std_msgs.msg
import Int8, Empty
22 rospy.loginfo(
"[midi_relative_converter] adjust axes size.")
24 rospy.logwarn(
"[midi_relative_converter] different axes size!!")
43 for i
in range(len(abs_axes)):
54 rel_axes = [
None] * len(abs_axes)
55 for i
in range(len(abs_axes)):
56 rel_axes[i] = self.
__convertAxis(abs_axes[i], in_origins[i], out_origins[i])
62 elif in_origin
is None:
64 elif abs_axis < in_origin:
65 rel_axis = (((abs_axis - 0.0) / (in_origin - 0.0)) * (out_origin - 0.0)) + 0.0
66 elif abs_axis == in_origin:
68 elif abs_axis > in_origin:
69 rel_axis = (((abs_axis - in_origin) / (1.0 - in_origin)) * (1.0 - out_origin)) + out_origin
77 for page
in range(max_page):
78 joy_pub = rospy.Publisher(
"/joy_relative/page_" + str(page), Joy)
80 rospy.Subscriber(
"/midi_relative_converter/command/switch_page", Int8, self.
switch_page_cmd_cb)
81 rospy.Subscriber(
"/midi_relative_converter/command/reset", Empty, self.
reset_cmd_cb)
87 if page >= 0
and page < len(self.
ac):
97 for i
in range(len(self.
ac)):
101 for i
in range(len(self.
ac)):
103 self.
ac[i].adjustAxesSize(len(abs_axes))
104 self.
ac[i].resetInputOrigins()
105 self.
ac[i].updateInputOrigins(abs_axes)
112 joy.header.stamp = rospy.Time.now()
113 joy.axes = self.
convert(data.axes)
114 joy.buttons = data.buttons
116 joy_pub = rospy.Publisher(
"/joy_relative/page_" + str(self.
crt_page), Joy)
126 rospy.init_node(
'joy_relative_converter')
130 if __name__ ==
'__main__':