00001
00002 import roslib
00003 roslib.load_manifest('cob_component_test')
00004
00005 import sys
00006 import time
00007 import unittest
00008 import rospy
00009 import rostest
00010 import actionlib
00011 import tf
00012
00013 from simple_script_server import *
00014 from gazebo.msg import *
00015 from geometry_msgs.msg import *
00016
00017 from math import *
00018
00019 class UnitTest(unittest.TestCase):
00020 def __init__(self, *args):
00021 super(UnitTest, self).__init__(*args)
00022 rospy.init_node('grasp_test')
00023 self.message_received = False
00024 self.sss=simple_script_server()
00025
00026 def setUp(self):
00027 self.errors = []
00028
00029 def test_grasp(self):
00030
00031
00032 try:
00033
00034 if not rospy.has_param('~test_duration'):
00035 self.fail('Parameter test_duration does not exist on ROS Parameter Server')
00036 test_duration = rospy.get_param('~test_duration')
00037
00038
00039 if not rospy.has_param('~grasp_object'):
00040 self.fail('Parameter grasp_object does not exist on ROS Parameter Server')
00041 grasp_object = rospy.get_param('~grasp_object')
00042
00043 except KeyError, e:
00044 self.fail('Parameters not set properly')
00045
00046 print """
00047 Test duration: %s
00048 Object to grasp: %s"""%(test_duration, grasp_object)
00049
00050
00051 sub_model_states = rospy.Subscriber("/gazebo/model_states", ModelStates, self.cb_model_states)
00052 sub_link_states = rospy.Subscriber("/gazebo/link_states", LinkStates, self.cb_link_states)
00053
00054
00055 self.listener = tf.TransformListener(True, rospy.Duration(10.0))
00056
00057
00058 self.sss.sleep(1)
00059 if grasp_object not in self.model_states.name:
00060 self.fail(grasp_object + " not spawned correctly")
00061
00062
00063 components_to_init = ['arm', 'tray', 'sdh', 'torso', 'base']
00064 for component in components_to_init:
00065 init_component = self.sss.init(component)
00066 if init_component.get_error_code() != 0:
00067 error_msg = 'Could not initialize ' + component
00068 self.fail(error_msg)
00069
00070
00071 handle_base = self.sss.move('base', 'kitchen', False)
00072 self.sss.move('tray', 'down', False)
00073 self.sss.move('arm', 'pregrasp', False)
00074 self.sss.move('sdh', 'cylopen', False)
00075 handle_base.wait()
00076
00077
00078
00079 obj_index = self.model_states.name.index(grasp_object)
00080
00081
00082 self.arm_7_link_index = self.link_states.name.index("arm_7_link")
00083
00084
00085 grasp_obj = self.trans_into_arm_7_link(self.model_states.pose[obj_index].position)
00086
00087
00088
00089 self.sss.move_cart_rel("arm", [[0.0, 0.0, 0.2], [0.0, 0.0, 0.0]])
00090
00091 self.sss.move("sdh", "cylclosed")
00092
00093 self.sss.move_cart_rel("arm", [[0.2, -0.1, -0.2], [0.0, 0.0, 0.0]])
00094
00095
00096 self.check_pos(self.link_states.pose[self.arm_7_link_index].position, self.model_states.pose[obj_index].position, 0.5, "sdh in kitchen")
00097
00098
00099 handle_arm = self.sss.move("arm", "grasp-to-tray", False)
00100
00101 self.sss.move("tray", "up")
00102 handle_arm.wait()
00103
00104
00105 self.check_pos(self.link_states.pose[self.arm_7_link_index].position, self.model_states.pose[obj_index].position, 0.5, "sdh over tray")
00106
00107
00108 self.sss.move_cart_rel("arm", [[-0.05, 0.0, 0.0], [0, 0, 0]])
00109 self.sss.move("sdh", "cylopen")
00110
00111
00112 self.sss.move('base', [0, -0.5, 0])
00113
00114
00115 des_pos_world = Point()
00116 des_pos_world.x = 0.3
00117 des_pos_world.y = -0.4
00118 des_pos_world.z = 0.885
00119 self.check_pos(des_pos_world, self.model_states.pose[obj_index].position, 0.5, "tray")
00120
00121
00122 self.sss.move("sdh", "cylclosed")
00123
00124
00125 self.sss.move("arm", "overtray")
00126 self.sss.move_cart_rel("arm", [[0.0, 0.0, -0.2], [0, 0, 0]])
00127 self.sss.move("arm", [[1.4272207239645427, -0.86918345596744029, -2.6785592907972724, -0.83566556448023821, 0.93072293274776374, 1.2925104647818602, -2.3042322384962883]])
00128 des_pos_world.x = 0.0
00129 des_pos_world.y = -1.2
00130 des_pos_world.z = 0.56
00131 des_pos_arm_7_link = self.trans_into_arm_7_link(des_pos_world)
00132
00133 x_dist_obj_arm_7_link = self.trans_into_arm_7_link(self.model_states.pose[obj_index].position).point.x
00134 self.sss.move_cart_rel("arm", [[(des_pos_arm_7_link.point.x - x_dist_obj_arm_7_link + 0.01), des_pos_arm_7_link.point.y, des_pos_arm_7_link.point.z], [0.0, 0.0, 0.0]])
00135 self.sss.move("sdh", "cylopen")
00136
00137
00138 des_pos_world.z = 0.55
00139 self.check_pos(des_pos_world, self.model_states.pose[obj_index].position, 0.2, "table")
00140
00141 self.sss.move_cart_rel("arm", [[0.5, 0.0, 0.0], [0.0, 0.0, 0.0]])
00142 self.sss.move("arm", "folded")
00143
00144
00145
00146
00147 def cb_model_states(self, msg):
00148 self.model_states = msg
00149
00150 def cb_link_states(self, msg):
00151 self.link_states = msg
00152
00153 def check_pos(self, des_pos, act_pos, tolerance, pos_name):
00154
00155 distance = self.calc_dist(des_pos, act_pos)
00156 print >> sys.stderr, "Distance to '", pos_name, "': ", distance
00157 if distance >= tolerance:
00158 error_msg = "Object not at desired position '" + pos_name + "'"
00159 self.fail(error_msg)
00160 else:
00161 print >> sys.stderr, "Object in/on '", pos_name, "'"
00162
00163 def calc_dist(self, des_pos, act_pos):
00164
00165 distance = sqrt((des_pos.x - act_pos.x)**2 + (des_pos.y - act_pos.y)**2 + (des_pos.z - act_pos.z)**2)
00166 return distance
00167
00168
00169 def trans_into_arm_7_link(self, coord_world):
00170
00171 coord_arm_7_link = PointStamped()
00172 coord_arm_7_link.header.stamp = rospy.Time.now()
00173 coord_arm_7_link.header.frame_id = "/map"
00174 coord_arm_7_link.point = coord_world
00175 self.sss.sleep(2)
00176
00177 if not self.sss.parse:
00178 coord_arm_7_link = self.listener.transformPoint('/arm_7_link', coord_arm_7_link)
00179
00180
00181 return coord_arm_7_link
00182
00183
00184 if __name__ == '__main__':
00185 try:
00186 rostest.run('rostest', 'grasp_test', UnitTest, sys.argv)
00187 except KeyboardInterrupt, e:
00188 pass
00189 print "exiting"