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 import random
00043 roslib.load_manifest(PKG)
00044 roslib.load_manifest('rostest')
00045
00046
00047 import sys, unittest
00048 import os, os.path, threading, time
00049 import rospy, rostest
00050 from std_msgs.msg import *
00051 from pr2_mechanism_controllers.msg import *
00052
00053 TEST_DURATION = 60.0
00054 COMMAND_INTERVAL = 10.0
00055 PI = 3.14159
00056
00057 CMD_SH_PAN_MIN = 0*(PI/4-1.5)
00058 CMD_SH_LFT_MIN = -0.4
00059 CMD_UA_ROL_MIN = 1.55-2.35
00060 CMD_EL_FLX_MIN = -2.3
00061 CMD_FA_ROL_MIN = 0*PI
00062 CMD_WR_FLX_MIN = -0.1
00063 CMD_WR_ROL_MIN = 0*PI
00064 CMD_GR_POS_MIN = 0.0
00065
00066 CMD_SH_PAN_MAX = 0*(PI/4+1.5)
00067 CMD_SH_LFT_MAX = 1.5
00068 CMD_UA_ROL_MAX = 1.55+2.35
00069 CMD_EL_FLX_MAX = 0.1
00070 CMD_FA_ROL_MAX = -0*PI
00071 CMD_WR_FLX_MAX = 2.2
00072 CMD_WR_ROL_MAX = -0*PI
00073 CMD_GR_POS_MAX = 0.548
00074
00075 if __name__ == '__main__':
00076 pub_l_shoulder_pan = rospy.Publisher("l_shoulder_pan_controller/set_command", Float64)
00077 pub_l_shoulder_lift = rospy.Publisher("l_shoulder_lift_controller/set_command", Float64)
00078 pub_l_upper_arm_roll = rospy.Publisher("l_upper_arm_roll_controller/set_command", Float64)
00079 pub_l_elbow_flex = rospy.Publisher("l_elbow_flex_controller/set_command", Float64)
00080 pub_l_elbow_roll = rospy.Publisher("l_elbow_roll_controller/set_command", Float64)
00081 pub_l_wrist_flex = rospy.Publisher("l_wrist_flex_controller/set_command", Float64)
00082 pub_l_wrist_roll = rospy.Publisher("l_wrist_roll_controller/set_command", Float64)
00083 pub_l_gripper = rospy.Publisher("l_gripper_controller/set_command", Float64)
00084 rospy.init_node(NAME, anonymous=True)
00085 timeout_t = time.time() + TEST_DURATION
00086 while time.time() < timeout_t:
00087 pub_l_shoulder_pan .publish(Float64(CMD_SH_PAN_MIN))
00088 pub_l_shoulder_lift .publish(Float64(CMD_SH_LFT_MIN))
00089 pub_l_upper_arm_roll .publish(Float64(CMD_UA_ROL_MIN))
00090 pub_l_elbow_flex .publish(Float64(CMD_EL_FLX_MIN))
00091 pub_l_elbow_roll .publish(Float64(CMD_FA_ROL_MIN))
00092 pub_l_wrist_flex .publish(Float64(CMD_WR_FLX_MIN))
00093 pub_l_wrist_roll .publish(Float64(CMD_WR_ROL_MIN))
00094 pub_l_gripper .publish(Float64(CMD_GR_POS_MIN))
00095 time.sleep(COMMAND_INTERVAL)
00096 pub_l_shoulder_pan .publish(Float64(CMD_SH_PAN_MAX))
00097 pub_l_shoulder_lift .publish(Float64(CMD_SH_LFT_MAX))
00098 pub_l_upper_arm_roll .publish(Float64(CMD_UA_ROL_MAX))
00099 pub_l_elbow_flex .publish(Float64(CMD_EL_FLX_MAX))
00100 pub_l_elbow_roll .publish(Float64(CMD_FA_ROL_MAX))
00101 pub_l_wrist_flex .publish(Float64(CMD_WR_FLX_MAX))
00102 pub_l_wrist_roll .publish(Float64(CMD_WR_ROL_MAX))
00103 pub_l_gripper .publish(Float64(CMD_GR_POS_MAX))
00104 time.sleep(COMMAND_INTERVAL)
00105
00106