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
00033
00034
00035
00036
00037 PKG = 'pr2_gazebo'
00038 NAME = 'grasp_preprogrammed'
00039
00040 import math
00041 import roslib
00042 roslib.load_manifest(PKG)
00043
00044 import sys, unittest
00045 import os, os.path, threading, time
00046 import rospy, rostest
00047
00048 from std_msgs.msg import Float64
00049 from nav_msgs.msg import Odometry
00050
00051
00052 CMD_POS_1 = 0.0
00053 CMD_POS_2 = 0.0
00054 CMD_POS_3 = 0.0
00055 CMD_POS_4 = 0.0
00056 CMD_POS_5 = 0.0
00057 CMD_POS_6 = 0.0
00058 CMD_POS_7 = 0.0
00059 LOWER_Z = 0.1
00060 PAN_RAD = 0.5
00061 G_OPEN = 0.058;
00062 G_CLOSE = 0.0199;
00063
00064 p3d_received = False
00065
00066 def p3dReceived(stuff):
00067 global p3d_received
00068 if not p3d_received:
00069 p3d_received = True
00070
00071 if __name__ == '__main__':
00072 pub_r_shoulder_pan = rospy.Publisher("r_shoulder_pan_position_controller/command", Float64)
00073 pub_r_shoulder_lift = rospy.Publisher("r_shoulder_lift_position_controller/command", Float64)
00074 pub_r_upper_arm_roll = rospy.Publisher("r_upper_arm_roll_position_controller/command", Float64)
00075 pub_r_elbow_flex = rospy.Publisher("r_elbow_flex_position_controller/command", Float64)
00076 pub_r_forearm_roll = rospy.Publisher("r_forearm_roll_position_controller/command", Float64)
00077 pub_r_wrist_flex = rospy.Publisher("r_wrist_flex_position_controller/command", Float64)
00078 pub_r_wrist_roll = rospy.Publisher("r_wrist_roll_position_controller/command", Float64)
00079 pub_r_gripper = rospy.Publisher("r_gripper_position_controller/command", Float64)
00080 rospy.Subscriber("r_gripper_palm_pose_ground_truth", Odometry, p3dReceived)
00081 rospy.init_node(NAME, anonymous=True)
00082
00083
00084
00085 while not p3d_received:
00086 time.sleep(1)
00087
00088
00089 pub_r_shoulder_pan .publish(Float64(CMD_POS_1))
00090 pub_r_shoulder_lift .publish(Float64(CMD_POS_2))
00091 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00092 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00093 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00094 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00095 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00096 pub_r_gripper .publish(Float64(G_OPEN))
00097 time.sleep(8)
00098
00099
00100 pub_r_shoulder_pan .publish(Float64(CMD_POS_1))
00101 pub_r_shoulder_lift .publish(Float64(CMD_POS_2+LOWER_Z))
00102 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00103 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00104 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00105 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00106 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00107 pub_r_gripper.publish(Float64(G_OPEN))
00108 time.sleep(2)
00109
00110
00111 pub_r_shoulder_pan .publish(Float64(CMD_POS_1))
00112 pub_r_shoulder_lift .publish(Float64(CMD_POS_2+LOWER_Z))
00113 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00114 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00115 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00116 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00117 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00118 pub_r_gripper.publish(Float64(G_CLOSE))
00119 time.sleep(8)
00120
00121
00122 pub_r_shoulder_pan .publish(Float64(CMD_POS_1))
00123 pub_r_shoulder_lift .publish(Float64(CMD_POS_2))
00124 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00125 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00126 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00127 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00128 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00129 pub_r_gripper.publish(Float64(G_CLOSE))
00130 time.sleep(20)
00131
00132
00133 pub_r_shoulder_pan .publish(Float64(CMD_POS_1+PAN_RAD))
00134 pub_r_shoulder_lift .publish(Float64(CMD_POS_2))
00135 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00136 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00137 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00138 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00139 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00140 pub_r_gripper.publish(Float64(G_CLOSE))
00141 time.sleep(10)
00142
00143
00144 pub_r_shoulder_pan .publish(Float64(CMD_POS_1+PAN_RAD))
00145 pub_r_shoulder_lift .publish(Float64(CMD_POS_2+LOWER_Z))
00146 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00147 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00148 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00149 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00150 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00151 pub_r_gripper.publish(Float64(G_CLOSE))
00152 time.sleep(8)
00153
00154
00155 pub_r_shoulder_pan .publish(Float64(CMD_POS_1+PAN_RAD))
00156 pub_r_shoulder_lift .publish(Float64(CMD_POS_2+LOWER_Z))
00157 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00158 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00159 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00160 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00161 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00162 pub_r_gripper.publish(Float64(G_OPEN))
00163 time.sleep(8)
00164
00165
00166 pub_r_shoulder_pan .publish(Float64(CMD_POS_1+PAN_RAD))
00167 pub_r_shoulder_lift .publish(Float64(CMD_POS_2))
00168 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00169 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00170 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00171 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00172 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00173 pub_r_gripper.publish(Float64(G_OPEN))
00174 time.sleep(10)
00175
00176
00177 pub_r_shoulder_pan .publish(Float64(CMD_POS_1))
00178 pub_r_shoulder_lift .publish(Float64(CMD_POS_2))
00179 pub_r_upper_arm_roll .publish(Float64(CMD_POS_3))
00180 pub_r_elbow_flex .publish(Float64(CMD_POS_4))
00181 pub_r_forearm_roll .publish(Float64(CMD_POS_5))
00182 pub_r_wrist_flex .publish(Float64(CMD_POS_6))
00183 pub_r_wrist_roll .publish(Float64(CMD_POS_7))
00184 pub_r_gripper.publish(Float64(G_CLOSE))
00185