5 imp.find_module(
"geometry_msgs")
7 import roslib; roslib.load_manifest(
'jsk_teleop_joy')
10 from geometry_msgs.msg
import PoseStamped
24 return val * val * sign
29 Left Analog x/y: translate x/y
30 Up/Down/Right/Left: rotate pitch/roll
35 Right Analog x/y: yaw/pitch of camera position (see parent class, RVizViewController)
36 R3(Right Analog button): suppressing buttons/sticks for controlling pose
37 R3 + L2 + R2: enable follow view mode
40 publish_pose [Boolean, default: True]: Publish or not pose
41 frame_id [String, default: map]: frame_id of publishing pose, this is overwritten by parameter, ~frame_id
42 pose [String, default: pose]: topic name for publishing pose
43 set_pose [String, default: set_pose]: topic name for setting pose by topic
47 RVizViewController.__init__(self, name, args)
59 if rospy.has_param(
'~frame_id'):
60 self.
frame_id = rospy.get_param(
'~frame_id')
64 pose.header.stamp = rospy.Time(0)
70 def joyCB(self, status, history):
72 if history.length() > 0:
73 latest = history.latest()
74 if status.R3
and status.L2
and status.R2
and not (latest.R3
and latest.L2
and latest.R2):
77 RVizViewController.joyCB(self, status, history)
78 new_pose = PoseStamped()
79 new_pose.header.frame_id = self.
frame_id
80 new_pose.header.stamp = rospy.Time(0.0)
87 dist = status.left_analog_y * status.left_analog_y + status.left_analog_x * status.left_analog_x
103 elif history.all(
lambda s: s.L2)
or history.all(
lambda s: s.R2):
107 local_move = numpy.array((x_diff, y_diff,
111 local_move = numpy.array((0.0, 0.0, 0.0, 1.0))
112 q = numpy.array((pre_pose.pose.orientation.x,
113 pre_pose.pose.orientation.y,
114 pre_pose.pose.orientation.z,
115 pre_pose.pose.orientation.w))
116 xyz_move = numpy.dot(tf.transformations.quaternion_matrix(q),
118 new_pose.pose.position.x = pre_pose.pose.position.x + xyz_move[0]
119 new_pose.pose.position.y = pre_pose.pose.position.y + xyz_move[1]
120 new_pose.pose.position.z = pre_pose.pose.position.z + xyz_move[2]
128 yaw = yaw + DTHETA * 5
129 elif history.all(
lambda s: s.L1):
130 yaw = yaw + DTHETA * 2
135 yaw = yaw - DTHETA * 5
136 elif history.all(
lambda s: s.R1):
137 yaw = yaw - DTHETA * 2
142 pitch = pitch + DTHETA * 5
143 elif history.all(
lambda s: s.up):
144 pitch = pitch + DTHETA * 2
146 pitch = pitch + DTHETA
149 pitch = pitch - DTHETA * 5
150 elif history.all(
lambda s: s.down):
151 pitch = pitch - DTHETA * 2
153 pitch = pitch - DTHETA
156 roll = roll + DTHETA * 5
157 elif history.all(
lambda s: s.right):
158 roll = roll + DTHETA * 2
163 roll = roll - DTHETA * 5
164 elif history.all(
lambda s: s.left):
165 roll = roll - DTHETA * 2
168 diff_q = tf.transformations.quaternion_from_euler(roll, pitch, yaw)
169 new_q = tf.transformations.quaternion_multiply(q, diff_q)
170 new_pose.pose.orientation.x = new_q[0]
171 new_pose.pose.orientation.y = new_q[1]
172 new_pose.pose.orientation.z = new_q[2]
173 new_pose.pose.orientation.w = new_q[3]
177 now = rospy.Time.from_sec(time.time())
179 if (now - self.
prev_time).to_sec() > 1 / 30.0: