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 PKG = 'life_test'
00034 import roslib; roslib.load_manifest(PKG)
00035 import rospy
00036 import actionlib
00037 from life_test.commanders.arm_cmder import ArmCmder
00038
00039 from pr2_controllers_msgs.msg import JointTrajectoryAction
00040 from arm_navigation_msgs.srv import SetPlanningSceneDiffRequest, SetPlanningSceneDiff
00041
00042 arm_ranges = {
00043 'r_shoulder_pan_joint': (-2.0, 0.4),
00044 'r_shoulder_lift_joint': (-0.4, 1.25),
00045 'r_upper_arm_roll_joint': (-3.5, 0.3),
00046 'r_elbow_flex_joint': (-2.0, -0.05)
00047 }
00048
00049 recovery_positions = {
00050 'r_shoulder_pan_joint': -0.8,
00051 'r_shoulder_lift_joint': 0.3,
00052 'r_upper_arm_roll_joint': 0.0,
00053 'r_elbow_flex_joint': -0.2
00054 }
00055
00056 if __name__ == '__main__':
00057 rospy.init_node('arm_cmder_client')
00058 client = actionlib.SimpleActionClient('collision_free_arm_trajectory_action_right_arm',
00059 JointTrajectoryAction)
00060 rospy.loginfo('Waiting for server for collision free arm commander')
00061 client.wait_for_server()
00062
00063 rospy.loginfo('Waiting for environment server')
00064
00065 rospy.wait_for_service('environment_server_right_arm/set_planning_scene_diff')
00066
00067 set_planning_scene_diff_client = rospy.ServiceProxy('environment_server_right_arm/set_planning_scene_diff',
00068 SetPlanningSceneDiff)
00069
00070
00071 planning_scene_diff_request = SetPlanningSceneDiffRequest()
00072 set_planning_scene_diff_client.call(planning_scene_diff_request)
00073
00074 rospy.loginfo('Sending arm commands')
00075
00076 my_rate = rospy.Rate(1.0)
00077
00078 recovery_client = actionlib.SimpleActionClient('r_arm_controller/joint_trajectory_action',
00079 JointTrajectoryAction)
00080
00081 cmder = ArmCmder(client, arm_ranges, recovery_client, recovery_positions)
00082
00083 while not rospy.is_shutdown():
00084 cmder.send_cmd()
00085 my_rate.sleep()