Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 import numpy as np
00033 
00034 import roslib
00035 roslib.load_manifest('hrl_pr2_arms')
00036 
00037 import rospy
00038 from robot_mechanism_controllers.msg import JTCartesianControllerState
00039 
00040 from ep_arm_base import EPArmBase, create_ep_arm
00041 from pr2_arm_cart_base import PR2ArmCartPostureBase, extract_twist
00042 from hrl_geom.pose_converter import PoseConv
00043 import hrl_geom.transformations as trans
00044 
00045 
00046 
00047 
00048 
00049 class PR2ArmJTranspose(PR2ArmCartPostureBase):
00050     def __init__(self, arm_side, urdf, base_link='torso_lift_link', end_link='%s_gripper_tool_frame', 
00051                  controller_name='/%s_cart', kdl_tree=None, timeout=1.):
00052         super(PR2ArmJTranspose, self).__init__(arm_side, urdf, base_link, end_link, 
00053                                                controller_name, kdl_tree, timeout)
00054         rospy.Subscriber(self.controller_name + '/state', JTCartesianControllerState, 
00055                          self._ctrl_state_cb)
00056         if self.wait_for_joint_angles(0):
00057             if not self.wait_for_ep(timeout):
00058                 rospy.logwarn("[pr2_arm_jt] Timed out waiting for EP.")
00059 
00060     def _ctrl_state_cb(self, ctrl_state):
00061         self._save_ep(PoseConv.to_homo_mat(ctrl_state.x_desi_filtered))
00062         with self.ctrl_state_lock:
00063             self.ctrl_state_dict["frame"] = ctrl_state.header.frame_id
00064             self.ctrl_state_dict["x_desi"] = PoseConv.to_pos_rot(ctrl_state.x_desi)
00065             self.ctrl_state_dict["xd_desi"] = extract_twist(ctrl_state.xd_desi)
00066             self.ctrl_state_dict["x_act"] = PoseConv.to_pos_rot(ctrl_state.x)
00067             self.ctrl_state_dict["xd_act"] = extract_twist(ctrl_state.xd)
00068             self.ctrl_state_dict["x_desi_filt"] = PoseConv.to_pos_rot(
00069                                                                 ctrl_state.x_desi_filtered)
00070             self.ctrl_state_dict["x_err"] = extract_twist(ctrl_state.x_err)
00071             self.ctrl_state_dict["tau_pose"] = np.array(ctrl_state.tau_pose)
00072             self.ctrl_state_dict["tau_posture"] = np.array(ctrl_state.tau_posture)
00073             self.ctrl_state_dict["tau"] = np.array(ctrl_state.tau)
00074             self.ctrl_state_dict["F"] = np.array([ctrl_state.F.force.x, 
00075                                                   ctrl_state.F.force.y,
00076                                                   ctrl_state.F.force.z,
00077                                                   ctrl_state.F.torque.x,
00078                                                   ctrl_state.F.torque.y,
00079                                                   ctrl_state.F.torque.z])