9 from geometry_msgs.msg
import PoseStamped
18 rospy.init_node(
"spacenav2pose")
27 self.
frame_id = rospy.get_param(
'~frame_id',
'/map')
29 self.
pose_pub = rospy.Publisher(rospy.get_param(
'~pose',
'pose'),
31 self.
pose_sub = rospy.Subscriber(rospy.get_param(
'~set_pose',
'set_pose'), PoseStamped, self.
setPoseCB)
33 joy_topic = rospy.get_param(
'~joy',
'/spacenav/joy')
35 rospy.logwarn(
"subscribe " + joy_topic)
37 self.
x_scale = rospy.get_param(
'~x_scale', 0.03)
38 self.
y_scale = rospy.get_param(
'~y_scale', 0.03)
39 self.
z_scale = rospy.get_param(
'~z_scale', 0.03)
41 self.
r_scale = rospy.get_param(
'~r_scale', 0.01)
42 self.
p_scale = rospy.get_param(
'~p_scale', 0.01)
43 self.
y_scale = rospy.get_param(
'~y_scale', 0.01)
50 pose.header.stamp = rospy.Time(0)
61 if b0 == 1
and self.
prev_joy.buttons[0] == 0:
64 rospy.logwarn(
"change mode to local mode")
67 rospy.logwarn(
"change mode to world mode")
73 new_pose = PoseStamped()
74 new_pose.header.frame_id = self.
frame_id 75 new_pose.header.stamp = rospy.Time(0.0)
78 q = numpy.array((pre_pose.pose.orientation.x,
79 pre_pose.pose.orientation.y,
80 pre_pose.pose.orientation.z,
81 pre_pose.pose.orientation.w))
83 x_diff = joy.axes[0] * self.
x_scale 84 y_diff = joy.axes[1] * self.
y_scale 85 z_diff = joy.axes[2] * self.
z_scale 86 local_move = numpy.array((x_diff, y_diff, z_diff, 1.0))
89 move_q = numpy.array((0.0, 0.0, 0.0, 1.0))
93 xyz_move = numpy.dot(tf.transformations.quaternion_matrix(move_q),
96 new_pose.pose.position.x = pre_pose.pose.position.x + xyz_move[0]
97 new_pose.pose.position.y = pre_pose.pose.position.y + xyz_move[1]
98 new_pose.pose.position.z = pre_pose.pose.position.z + xyz_move[2]
101 roll = self.
r_scale * joy.axes[3]
102 pitch = self.
p_scale * joy.axes[4]
103 yaw = self.
y_scale * joy.axes[5]
105 diff_q = tf.transformations.quaternion_from_euler(roll, pitch, yaw)
108 new_q = tf.transformations.quaternion_multiply(diff_q, q)
110 new_q = tf.transformations.quaternion_multiply(q, diff_q)
112 new_pose.pose.orientation.x = new_q[0]
113 new_pose.pose.orientation.y = new_q[1]
114 new_pose.pose.orientation.z = new_q[2]
115 new_pose.pose.orientation.w = new_q[3]
119 now = rospy.Time.from_sec(time.time())
121 if (now - self.
prev_time).to_sec() > 1 / 30.0:
128 if __name__ ==
'__main__':
def setPoseCB(self, pose)