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
00033 import roslib
00034 roslib.load_manifest('pr2_plugs_gazebo_demo')
00035 import rospy
00036 from pr2_plugs_gazebo_demo.srv import ExecuteCartesianIKTrajectory
00037 from geometry_msgs.msg import Pose, PoseWithCovarianceStamped
00038 from nav_msgs.msg import Odometry
00039 import time
00040 import sys
00041 import pdb
00042 import tf
00043 import tf.transformations as tft
00044
00045 import actionlib
00046 from pr2_controllers_msgs.msg import Pr2GripperCommandAction,Pr2GripperCommandGoal
00047
00048 plug_p = [0,0,0]
00049 plug_q = [0,0,0,1]
00050 plug_e = [0,0,0]
00051 got_plug = False
00052
00053
00054
00055
00056 gripper_error = [1 1 1 1 1 1 1]
00057
00058
00059 def gotToIKPose(position,orientation):
00060 ik_pub = rospy.Publisher('plugs_ik_node/pose_command', PoseWithCovarianceStamped)
00061 p = PoseWithCovarianceStamped()
00062 p.header.frame_id = 'base_link'
00063 p.header.stamp = rospy.get_rostime()
00064 p.pose.pose = Pose()
00065 p.pose.pose.position.x = position[0]
00066 p.pose.pose.position.y = position[1]
00067 p.pose.pose.position.z = position[2]
00068 p.pose.pose.orientation.x = orientation[0]
00069 p.pose.pose.orientation.y = orientation[1]
00070 p.pose.pose.orientation.z = orientation[2]
00071 p.pose.pose.orientation.w = orientation[3]
00072
00073 ik_pub.publish(p)
00074 (trans, rot) = tf_listener.lookupTransform('base_link', 'r_wrist_roll_link', rospy.Time(0))
00075
00076
00077 (trans, rot) = tf_listener.lookupTransform('base_link', 'r_wrist_roll_link', rospy.Time(0))
00078 while abs(trans[0]-position[0]) > 0.001 \
00079 or abs(trans[1]-position[1]) > 0.001 \
00080 or abs(trans[2]-position[2]) > 0.001 \
00081 or abs(rot[0]-orientation[0]) > 0.001:
00082 (trans, rot) = tf_listener.lookupTransform('base_link', 'r_wrist_roll_link', rospy.Time(0))
00083 print "goal: ",position[0],position[1],position[2],orientation[0],orientation[1],orientation[2],orientation[3]
00084 print "curr: ",trans[0],trans[1],trans[2],rot[0],rot[1],rot[2],rot[3]
00085 time.sleep(1)
00086
00087 return
00088
00089 def plugP3DInput(p3d):
00090 global plug_p, plug_q, plug_e, got_plug
00091 plug_p = [p3d.pose.pose.position.x, p3d.pose.pose.position.y, p3d.pose.pose.position.z]
00092 plug_q = [p3d.pose.pose.orientation.x, p3d.pose.pose.orientation.y, p3d.pose.pose.orientation.z, p3d.pose.pose.orientation.w]
00093 plug_e = tft.euler_from_quaternion(plug_q)
00094 got_plug = True
00095
00096
00097 if __name__ == "__main__":
00098 rospy.init_node("test_cartesian_ik_trajectory_executer")
00099 rospy.Subscriber("/plug/plug_pose_ground_truth", Odometry, plugP3DInput)
00100 tf_listener = tf.TransformListener()
00101
00102
00103 while not got_plug:
00104 print "waiting for plug pose: ",got_plug
00105 time.sleep(1.)
00106
00107
00108 client = actionlib.SimpleActionClient('r_gripper_controller/gripper_action',Pr2GripperCommandAction)
00109 print "waiting for gripper_action server"
00110 client.wait_for_server()
00111 gripper_goal = Pr2GripperCommandGoal()
00112 gripper_goal.command.position = 0.08
00113 gripper_goal.command.max_effort = 10.0
00114 client.send_goal(gripper_goal)
00115 client.wait_for_result()
00116
00117 joint_names = ["r_shoulder_pan_joint",
00118 "r_shoulder_lift_joint",
00119 "r_upper_arm_roll_joint",
00120 "r_elbow_flex_joint",
00121 "r_forearm_roll_joint",
00122 "r_wrist_flex_joint",
00123 "r_wrist_roll_joint"]
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 position = [plug_p[0] ,plug_p[1] - 0.18 ,plug_p[2]-0.04 ]
00135 orientation = [.0, .0, 0.7071, 0.7071]
00136 print "goal: ",position[0],position[1],position[2],orientation[0],orientation[1],orientation[2],orientation[3]
00137
00138 gotToIKPose(position,orientation)
00139
00140
00141
00142 client = actionlib.SimpleActionClient('r_gripper_controller/gripper_action',Pr2GripperCommandAction)
00143 client.wait_for_server()
00144 gripper_goal = Pr2GripperCommandGoal()
00145 gripper_goal.command.position = 0.0
00146 gripper_goal.command.max_effort = 100.0
00147 client.send_goal(gripper_goal)
00148
00149
00150 position = [.76, -.19, .83]
00151 position = [plug_p[0],plug_p[1] - 0.2 ,plug_p[2]-0.2 ]
00152 orientation = [.0, .0, 0.7071, 0.7071]
00153 orientation = [.0, .0, 0.0, 1.0]
00154
00155 gotToIKPose(position,orientation)