11 import roslib;roslib.load_manifest(PKG)
13 from sensor_msgs.msg
import Joy
32 global x_max, y_max, z_max, r_max, sr_max
33 global x_small_max, y_small_max, z_small_max, r_small_max, sr_small_max
37 x_v1,y_v1,z_v1,r_v1,sr_v1 = a[13:]
38 x_v2,y_v2,z_v2,r_v2,sr_v2 = a[0:5]
46 x.data = x_max * (x_v1+1)/2 + x_small_max * (x_v2+1)/2;
47 y.data = y_max * (y_v1+1)/2 + y_small_max * (y_v2+1)/2;
48 z.data = z_max * (z_v1+1)/2 + z_small_max * (z_v2+1)/2;
49 r.data = r_max * (r_v1+1)/2 + r_small_max * (r_v2+1)/2;
50 sr.data= sr_max * (sr_v1+1)/2 + sr_small_max * (sr_v2+1)/2;
52 x.data = max(MIN_VALUE,x.data)
53 y.data = max(MIN_VALUE,y.data)
54 z.data = max(MIN_VALUE,z.data)
55 r.data = max(MIN_VALUE,r.data)
56 sr.data = max(MIN_VALUE,sr.data)
62 set_sr_pub.publish(sr)
64 if __name__ ==
"__main__":
65 rospy.init_node(
"transformable_joy_configure")
66 set_x_pub = rospy.Publisher(
"set_x", Float32)
67 set_y_pub = rospy.Publisher(
"set_y", Float32)
68 set_z_pub = rospy.Publisher(
"set_z", Float32)
69 set_r_pub = rospy.Publisher(
"set_radius", Float32)
70 set_sr_pub = rospy.Publisher(
"set_small_radius", Float32)
72 x_max = rospy.get_param(
"~x_max")
73 y_max = rospy.get_param(
"~y_max")
74 z_max = rospy.get_param(
"~z_max")
75 r_max = rospy.get_param(
"~r_max")
76 sr_max = rospy.get_param(
"~sr_max")
78 x_small_max = rospy.get_param(
"~x_small_max")
79 y_small_max = rospy.get_param(
"~y_small_max")
80 z_small_max = rospy.get_param(
"~z_small_max")
81 r_small_max = rospy.get_param(
"~r_small_max")
82 sr_small_max = rospy.get_param(
"~sr_small_max")
85 s = rospy.Subscriber(
"input_joy", Joy, callback)