5 imp.find_module(
"actionlib")
7 import roslib; roslib.load_manifest(
'jsk_teleop_joy')
10 from jsk_teleop_joy.joy_pose_6d
import JoyPose6D
11 from jsk_footstep_msgs.msg
import PlanFootstepsAction, PlanFootstepsGoal, Footstep, FootstepArray
12 from std_msgs.msg
import UInt8
13 from geometry_msgs.msg
import Pose
19 mat = quaternion_matrix(numpy.array((pose.orientation.x,
24 mat[0, 3] = pose.position.x
25 mat[1, 3] = pose.position.y
26 mat[2, 3] = pose.position.z
29 q = quaternion_from_matrix(mat)
31 pose.orientation.x = q[0]
32 pose.orientation.y = q[1]
33 pose.orientation.z = q[2]
34 pose.orientation.w = q[3]
35 pose.position.x = mat[0, 3]
36 pose.position.y = mat[1, 3]
37 pose.position.z = mat[2, 3]
43 JoyPose6D.__init__(self, name, args)
44 self.supportFollowView(
True)
45 self.
frame_id = self.getArg(
'frame_id',
'/map')
56 def joyCB(self, status, history):
57 JoyPose6D.joyCB(self, status, history)
70 latest = history.latest()
73 if status.triangle
and not latest.triangle:
75 elif status.cross
and not latest.cross:
77 if status.circle
and not latest.circle:
80 lleg_offset.position.y = 0.1
81 lleg_offset.orientation.w = 1.0
83 rleg_offset.position.y = -0.1
84 rleg_offset.orientation.w = 1.0
88 new_lleg_mat = numpy.dot(base_mat, left_offset_mat)
89 new_rleg_mat = numpy.dot(base_mat, right_offset_mat)