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 import random
00038 import copy
00039 import math
00040 from time import sleep
00041
00042 from pr2_controllers_msgs.msg import *
00043 from trajectory_msgs.msg import JointTrajectoryPoint
00044 from mapping_msgs.msg import CollisionObject, CollisionObjectOperation, AttachedCollisionObject
00045 from geometric_shapes_msgs.msg import Shape
00046 from geometry_msgs.msg import Pose
00047 from actionlib_msgs.msg import GoalStatus
00048
00049 from life_test.commanders.arm_cmder import ArmCmder
00050
00051 COLLISION_TOPIC = "collision_object"
00052
00053
00054 ranges = {
00055 'r_shoulder_pan_joint': (-2.0, -0.4),
00056 'r_shoulder_lift_joint': (-0.4, 1.25),
00057 'r_upper_arm_roll_joint': (-3.1, 0),
00058 'r_elbow_flex_joint': (-2.0, -0.05),
00059 'r_forearm_roll_joint': (-3.14, 3.14),
00060 'r_wrist_flex_joint': (-1.8, -0.2),
00061 'r_wrist_roll_joint': (-3.14, 3.14),
00062 'l_shoulder_pan_joint': (0.4, 2.0),
00063 'l_shoulder_lift_joint': (-0.4, 1.25),
00064 'l_upper_arm_roll_joint': (0, 3.1),
00065 'l_elbow_flex_joint': (-2.0, -0.05),
00066 'l_forearm_roll_joint': (-3.14, 3.14),
00067 'l_wrist_flex_joint': (-1.8, -0.2),
00068 'l_wrist_roll_joint': (-3.14, 3.14)
00069 }
00070
00071 recovery_positions = {
00072 'r_shoulder_pan_joint': - math.pi / 4,
00073 'r_shoulder_lift_joint': 0.0,
00074 'r_upper_arm_roll_joint': 0.0,
00075 'r_elbow_flex_joint': 0.0,
00076 'r_forearm_roll_joint': 0.0,
00077 'r_wrist_flex_joint': 0.0,
00078 'r_wrist_roll_joint': 0.0,
00079 'l_shoulder_pan_joint': math.pi / 4,
00080 'l_shoulder_lift_joint': 0.0,
00081 'l_upper_arm_roll_joint': 0.0,
00082 'l_elbow_flex_joint': 0.0,
00083 'l_forearm_roll_joint': 0.0,
00084 'l_wrist_flex_joint': 0.0,
00085 'l_wrist_roll_joint': 0.0
00086 }
00087
00088 def get_virtual_gloves():
00089 r_glove = AttachedCollisionObject()
00090 r_glove.object.header.stamp = rospy.get_rostime()
00091 r_glove.object.header.frame_id = '/r_gripper_palm_link'
00092 r_glove.link_name = 'r_gripper_palm_link'
00093
00094 r_glove.object.id = 'r_gripper_glove'
00095 r_glove.object.operation.operation = CollisionObjectOperation.ADD
00096
00097 glove_shape = Shape()
00098 glove_shape.type = Shape.BOX
00099 glove_shape.dimensions = [ 0.25, 0.18, 0.1 ]
00100 glove_pose = Pose()
00101 glove_pose.orientation.w = 1
00102 glove_pose.position.x = 0.1
00103
00104
00105
00106 r_glove.touch_links = ['r_gripper_palm_link',
00107 'r_gripper_l_finger_link',
00108 'r_gripper_l_finger_tip_link',
00109 'r_gripper_r_finger_link',
00110 'r_gripper_r_finger_tip_link',
00111 'r_wrist_roll_link',
00112 'r_wrist_flex_link',
00113 'r_forearm_link']
00114
00115 r_glove.object.shapes.append(glove_shape)
00116 r_glove.object.poses.append(glove_pose)
00117
00118 l_glove = copy.deepcopy(r_glove)
00119 l_glove.object.id = 'l_gripper_glove'
00120 l_glove.object.header.frame_id = '/l_gripper_palm_link'
00121 l_glove.link_name = 'l_gripper_palm_link'
00122 l_glove.touch_links = [ 'l' + name[1:] for name in r_glove.touch_links ]
00123
00124 return r_glove, l_glove
00125
00126
00127
00128 def get_virtual_table(height = 0.42):
00129 table_msg = CollisionObject()
00130
00131 table_msg.id = "table"
00132 table_msg.operation.operation = CollisionObjectOperation.ADD
00133
00134 table_msg.header.stamp = rospy.get_rostime()
00135 table_msg.header.frame_id = "base_footprint"
00136
00137 side_box = Shape()
00138 side_box.type = Shape.BOX
00139 side_box.dimensions = [ 3.0, 1.0, height ]
00140
00141 front_box = Shape()
00142 front_box.type = Shape.BOX
00143 front_box.dimensions = [ 1.0, 3.0, height ]
00144
00145 pose = Pose()
00146 pose.position.x = 0.0
00147 pose.position.y = 0.0
00148 pose.position.z = height / 2
00149 pose.orientation.x = 0
00150 pose.orientation.y = 0
00151 pose.orientation.z = 0
00152 pose.orientation.w = 1
00153
00154 l_side_pose = copy.deepcopy(pose)
00155 l_side_pose.position.y = 0.85
00156
00157 r_side_pose = copy.deepcopy(pose)
00158 r_side_pose.position.y = -0.85
00159
00160 front_pose = copy.deepcopy(pose)
00161 front_pose.position.x = 0.85
00162
00163 table_msg.shapes = [ side_box, side_box, front_box ]
00164 table_msg.poses = [ l_side_pose, r_side_pose, front_pose ]
00165
00166 return table_msg
00167
00168 if __name__ == '__main__':
00169 rospy.init_node('arm_cmder_client')
00170 client = actionlib.SimpleActionClient('collision_free_arm_trajectory_action_both_arms',
00171 JointTrajectoryAction)
00172 rospy.loginfo('Waiting for server for right collision free arm commander')
00173 client.wait_for_server()
00174
00175 rospy.loginfo('Right, left arm commanders ready')
00176
00177 table_pub = rospy.Publisher(COLLISION_TOPIC, CollisionObject, latch = True)
00178 table_pub.publish(get_virtual_table())
00179
00180 glove_pub = rospy.Publisher("attached_collision_object", AttachedCollisionObject, latch = True)
00181 r_glove, l_glove = get_virtual_gloves()
00182 glove_pub.publish(r_glove)
00183 sleep(1)
00184 glove_pub.publish(l_glove)
00185
00186
00187 recovery_client = actionlib.SimpleActionClient('both_arms_controller/joint_trajectory_action',
00188 JointTrajectoryAction)
00189
00190 cmder = ArmCmder(client, ranges, recovery_client, recovery_positions)
00191
00192 while not rospy.is_shutdown():
00193 rospy.logdebug('Sending goal to arms.')
00194 cmder.send_cmd()
00195
00196 sleep(2.0)
00197