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_arm_gazebo'
00038 NAME = 'l_arm_setting'
00039
00040 import math
00041 import roslib
00042 roslib.load_manifest(PKG)
00043 roslib.load_manifest('rostest')
00044
00045
00046 import sys, unittest
00047 import os, os.path, threading, time
00048 import rospy, rostest
00049 from std_msgs.msg import *
00050 from pr2_mechanism_controllers.msg import *
00051
00052 PI = 3.14159
00053
00054 CMD_SH_PAN = 0.0*(PI/4+1.5 )
00055 CMD_SH_LFT = 1.0*(1.5 )
00056 CMD_UA_ROL = 1.0*(1.55+2.35 )
00057 CMD_EL_FLX = 1.0*(0.1 )
00058 CMD_FA_ROL = 1.0*(-0*PI )
00059 CMD_WR_FLX = 1.0*(2.2 )
00060 CMD_WR_ROL = 1.0*(-0*PI )
00061 CMD_GR_POS = 1.0*(0.548 )
00062
00063 if __name__ == '__main__':
00064 pub_l_shoulder_pan = rospy.Publisher("l_shoulder_pan_controller/set_command", Float64)
00065 pub_l_shoulder_lift = rospy.Publisher("l_shoulder_lift_controller/set_command", Float64)
00066 pub_l_upper_arm_roll = rospy.Publisher("l_upper_arm_roll_controller/set_command", Float64)
00067 pub_l_elbow_flex = rospy.Publisher("l_elbow_flex_controller/set_command", Float64)
00068 pub_l_elbow_roll = rospy.Publisher("l_elbow_roll_controller/set_command", Float64)
00069 pub_l_wrist_flex = rospy.Publisher("l_wrist_flex_controller/set_command", Float64)
00070 pub_l_wrist_roll = rospy.Publisher("l_wrist_roll_controller/set_command", Float64)
00071 pub_l_gripper = rospy.Publisher("l_gripper_controller/set_command", Float64)
00072 rospy.init_node(NAME, anonymous=True)
00073 timeout_t = time.time() + 10.0
00074 while time.time() < timeout_t:
00075 pub_l_shoulder_pan .publish(Float64(CMD_SH_PAN))
00076 pub_l_shoulder_lift .publish(Float64(CMD_SH_LFT))
00077 pub_l_upper_arm_roll .publish(Float64(CMD_UA_ROL))
00078 pub_l_elbow_flex .publish(Float64(CMD_EL_FLX))
00079 pub_l_elbow_roll .publish(Float64(CMD_FA_ROL))
00080 pub_l_wrist_flex .publish(Float64(CMD_WR_FLX))
00081 pub_l_wrist_roll .publish(Float64(CMD_WR_ROL))
00082 pub_l_gripper .publish(Float64(CMD_GR_POS))
00083 time.sleep(0.2)
00084