$search
00001 import roslib 00002 roslib.load_manifest('srs_states') 00003 import rospy 00004 import smach 00005 import smach_ros 00006 00007 from math import * 00008 import copy 00009 from struct import * 00010 00011 from simple_script_server import * 00012 sss = simple_script_server() 00013 00014 from cob_object_detection_msgs.msg import * 00015 from cob_object_detection_msgs.srv import * 00016 from shared_state_information import * 00017 from eval_objects import * 00018 from cob_3d_mapping_msgs.msg import * 00019 #import service form semantic KB 00020 from srs_knowledge.srv import * 00021 00022 ## Detect state 00023 # 00024 # This state will try to detect an object. 00025 00026 00027 class detect_object(smach.State): 00028 def __init__(self,object_name = "",max_retries = 1): 00029 smach.State.__init__( 00030 self, 00031 outcomes=['succeeded','retry','no_more_retries','failed','preempted'], 00032 input_keys=['object_name'], 00033 output_keys=['object','object_pose']) 00034 00035 self.object_list = DetectionArray() 00036 self.max_retries = max_retries 00037 self.retries = 0 00038 self.object_name = object_name 00039 self.srv_name_object_detection = '/object_detection/detect_object' 00040 00041 self.torso_poses = [] 00042 self.torso_poses.append("back_right") 00043 self.torso_poses.append("back_right") 00044 #self.torso_poses.append("back_right_extreme") 00045 self.torso_poses.append("back") 00046 self.torso_poses.append("back") 00047 #self.torso_poses.append("back_extreme") 00048 self.torso_poses.append("back_left") 00049 self.torso_poses.append("back_left") 00050 #self.torso_poses.append("back_left_extreme") 00051 self.the_object = '' 00052 self.the_object_pose = '' 00053 00054 00055 def execute(self, userdata): 00056 00057 global current_task_info 00058 #userdata.object_name = "milk" 00059 # if the object has been identified, and there was no base movement of grasp, then no need to detect again 00060 if current_task_info.get_object_identification_state() == True: 00061 userdata.object_pose = self.the_object_pose 00062 userdata.object = self.the_object 00063 return 'succeeded' 00064 00065 if self.preempt_requested(): 00066 self.service_preempt() 00067 return 'preempted' 00068 00069 """ 00070 # checking extra information 00071 if userdata.key_region == '': 00072 pass #normal detection 00073 else: 00074 pass #detection in bounding box specified by key_region 00075 """ 00076 #add initial value to output keys 00077 userdata.object = "" 00078 userdata.object_pose="" 00079 00080 rospy.loginfo("object_name: %s", userdata.object_name) 00081 00082 # determine object name 00083 if self.object_name != "": 00084 object_name = self.object_name 00085 elif type(userdata.object_name) is str: 00086 object_name = userdata.object_name 00087 else: # this should never happen 00088 rospy.logerr("Invalid userdata 'object_name'") 00089 self.retries = 0 00090 return 'failed' 00091 00092 # check if maximum retries reached 00093 if self.retries > self.max_retries: 00094 self.retries = 0 00095 handle_torso = sss.move("torso","home",False) 00096 handle_torso.wait() 00097 return 'no_more_retries' 00098 00099 # move sdh as feedback 00100 sss.move("sdh","cylclosed",False) 00101 00102 # make the robot ready to inspect the scene 00103 if self.retries == 0: # only move arm, sdh and head for the first try 00104 rospy.loginfo ("object_name: %s", object_name) 00105 sss.say([current_task_info.speaking_language['Search'] + object_name + "."],False) 00106 handle_arm = sss.move("arm","folded-to-look_at_table",False) 00107 handle_torso = sss.move("torso","shake",False) 00108 handle_head = sss.move("head","back",False) 00109 00110 if self.preempt_requested(): 00111 self.service_preempt() 00112 #handle_base.set_failed(4) 00113 handle_arm.client.cancel_goal() 00114 handle_torso.client.cancel_goal() 00115 handle_head.client.cancel_goal() 00116 return 'preempted' 00117 else: 00118 handle_arm.wait() 00119 handle_head.wait() 00120 handle_torso.wait() 00121 00122 handle_torso = sss.move("torso",self.torso_poses[self.retries % len(self.torso_poses)]) # have an other viewing point for each retry 00123 00124 # move sdh as feedback 00125 sss.move("sdh","home",False) 00126 00127 # wait for image to become stable 00128 sss.sleep(2) 00129 00130 00131 # check if object detection service is available 00132 try: 00133 rospy.wait_for_service(self.srv_name_object_detection,10) 00134 except rospy.ROSException, e: 00135 print "Service not available: %s"%e 00136 self.retries = 0 # no object found within min_dist start value 00137 return 'failed' 00138 00139 # call object detection service 00140 try: 00141 detector_service = rospy.ServiceProxy(self.srv_name_object_detection, DetectObjects) 00142 req = DetectObjectsRequest() 00143 req.object_name.data = object_name 00144 res = detector_service(req) 00145 except rospy.ServiceException, e: 00146 print "Service call failed: %s"%e 00147 self.retries = 0 00148 return 'failed' 00149 00150 # check for no objects 00151 if len(res.object_list.detections) <= 0: 00152 rospy.logerr("No objects found") 00153 self.retries += 1 00154 return 'retry' 00155 00156 # select nearest object in x-y-plane in head_camera_left_link 00157 min_dist = 2 # start value in m 00158 obj = Detection() 00159 for item in res.object_list.detections: 00160 dist = sqrt(item.pose.pose.position.x*item.pose.pose.position.x+item.pose.pose.position.y*item.pose.pose.position.y) 00161 if dist < min_dist: 00162 min_dist = dist 00163 obj = copy.deepcopy(item) 00164 00165 # check if an object could be found within the min_dist start value 00166 if obj.label == "": 00167 rospy.logerr("Object not within target range") 00168 self.retries += 1 00169 return 'retry' 00170 00171 #check if label of object fits to requested object_name 00172 if obj.label != object_name: 00173 rospy.logerr("The object name doesn't fit.") 00174 self.retries += 1 00175 return 'retry' 00176 00177 # we succeeded to detect an object 00178 userdata.object = obj 00179 self.the_object = obj 00180 object_pose_map = PoseStamped() 00181 self.retries = 0 00182 00183 global listener 00184 00185 try: 00186 #transform object_pose into base_link 00187 object_pose_in = copy.deepcopy(obj.pose) 00188 object_pose_in.header.stamp = listener.getLatestCommonTime("/map",object_pose_in.header.frame_id) 00189 object_pose_map = listener.transformPose("/map", object_pose_in) 00190 obj.pose = copy.deepcopy(object_pose_map) 00191 userdata.object = obj 00192 except rospy.ROSException, e: 00193 print "Transformation not possible: %s"%e 00194 return 'failed' 00195 00196 #print object_pose_map 00197 00198 userdata.object_pose=object_pose_map 00199 self.the_object_pose=object_pose_map 00200 00201 if self.preempt_requested(): 00202 self.service_preempt() 00203 return 'preempted' 00204 00205 # remember the object has been identified, if there is no base movement of grasp, no need to detect again 00206 current_task_info.set_object_identification_state(True) 00207 return 'succeeded' 00208 00209 00210 """Verifies whether the object expected at target_object_pose is actually there. 00211 If yes, verfified_target_object_pose is returned.""" 00212 class VerifyObject(smach.State): 00213 00214 def __init__(self): 00215 00216 smach.State.__init__( 00217 self, 00218 outcomes=['succeeded', 'failed', 'not_completed', 'preempted'], 00219 input_keys=['object_id','target_object_pose'], 00220 output_keys=['verfified_target_object_pose']) 00221 self.eo = EvalObjects() 00222 #self.client = actionlib.SimpleActionClient('trigger_mapping', TriggerMappingAction) 00223 00224 def execute(self, userdata): 00225 #object_to_search =self.eo.semantics_db_get_object_info(userdata.object_id) 00226 #print "Searching for object at " + str(object_to_search.objectPose.position.x) + ", " + str(object_to_search.objectPose.position.y) 00227 """TODO: get classID for object_id or have class_id as input""" 00228 object_list_map = self.eo.map_list_objects(1)#object_to_search.classID) 00229 #if object_to_search.classID == 1: #table 00230 verified_table = self.eo.verify_table(userdata.target_object_pose, object_list_map) 00231 if verified_table: 00232 userdata.verfified_target_object_pose = verified_table.pose.pose 00233 print "table " + str(userdata.target_object_pose.position.x) + "," + str(userdata.target_object_pose.position.y) + " found at " + str(verified_table.pose.pose.position.x) + "," + str(verified_table.pose.pose.position.y) 00234 return 'succeeded' 00235 else: 00236 print "table " + str(userdata.target_object_pose.position.x) + "," + str(userdata.target_object_pose.position.y) + " not found" 00237 return 'not_completed' 00238 #else: 00239 # print 'Object class not supported' 00240 # return 'failed' 00241 00242 """Verifies whether the object expected at target_object_pose is actually there. 00243 If yes, verfified_target_object_pose is returned.""" 00244 class VerifyObjectByName(smach.State): 00245 00246 def __init__(self): 00247 00248 smach.State.__init__( 00249 self, 00250 outcomes=['succeeded', 'failed', 'not_completed', 'preempted'], 00251 input_keys=['object_name'], 00252 output_keys=['verfified_target_object_pose']) 00253 self.eo = EvalObjects() 00254 #self.client = actionlib.SimpleActionClient('trigger_mapping', TriggerMappingAction) 00255 00256 def execute(self, userdata): 00257 00258 target_object_pose ='' 00259 object_id = -1000 00260 all_workspaces_on_map = '' 00261 index_of_the_target_workspace = '' 00262 00263 try: 00264 getWorkspace = rospy.ServiceProxy('get_workspace_on_map', GetWorkspaceOnMap) 00265 all_workspaces_on_map = getWorkspace(os.environ['ROBOT_ENV'], True) 00266 00267 #get the index of the target workspace e.g. table0 00268 index_of_the_target_workspace = all_workspaces_on_map.objects.index(userdata.object_name) 00269 #get the pose of the workspace from knowledge service 00270 target_object_pose = all_workspaces_on_map.objectsInfo[index_of_the_target_workspace].pose 00271 #get the houseHoldID of the workspace 00272 object_id = all_workspaces_on_map.houseHoldId[index_of_the_target_workspace] 00273 00274 rospy.loginfo ("target name: %s", userdata.object_name) 00275 rospy.loginfo ("target pose: %s", target_object_pose) 00276 rospy.loginfo ("target id: %s", object_id) 00277 00278 00279 except rospy.ServiceException, e: 00280 print "Service call failed: %s"%e 00281 return 'failed' 00282 00283 """ 00284 #checking object id in HHDB, maybe required for more complicated verification 00285 if object_id == -1000: 00286 #the object is not available in the HH database 00287 #verification not possible 00288 return 'not_completed' 00289 """ 00290 00291 #object_to_search =self.eo.semantics_db_get_object_info(userdata.object_id) 00292 #print "Searching for object at " + str(object_to_search.objectPose.position.x) + ", " + str(object_to_search.objectPose.position.y) 00293 """TODO: get classID for object_id or have class_id as input""" 00294 object_list_map = self.eo.map_list_objects(1)#object_to_search.classID) 00295 print "object list map",object_list_map 00296 #if object_to_search.classID == 1: #table 00297 verified_table = self.eo.verify_table(target_object_pose, object_list_map) 00298 if verified_table: 00299 userdata.verfified_target_object_pose = verified_table.pose.pose 00300 print "table " + str(userdata.target_object_pose.position.x) + "," + str(userdata.target_object_pose.position.y) + " found at " + str(verified_table.pose.pose.position.x) + "," + str(verified_table.pose.pose.position.y) 00301 return 'succeeded' 00302 else: 00303 print "table " + str(target_object_pose.position.x) + "," + str(target_object_pose.position.y) + " not found" 00304 return 'not_completed' 00305 #else: 00306 # print 'Object class not supported' 00307 # return 'failed' 00308 00309 """Observes the space over a table and returns objects as bounding boxes""" 00310 class GetTableObjectCluster(smach.State): 00311 00312 def __init__(self): 00313 00314 smach.State.__init__( 00315 self, 00316 outcomes=['succeeded', 'failed', 'not_completed', 'preempted'], 00317 input_keys=['target_table_pose'], 00318 output_keys=['object_cluster']) 00319 self.eo = EvalObjects() 00320 self.client = actionlib.SimpleActionClient('table_object_cluster', TableObjectClusterAction) 00321 00322 def execute(self, userdata): 00323 #object_to_search =self.eo.semantics_db_get_object_info(userdata.object_id) 00324 #print "Searching for object at " + str(object_to_search.objectPose.position.x) + ", " + str(object_to_search.objectPose.position.y) 00325 object_list_map = self.eo.map_list_objects(1)#object_to_search.classID) 00326 #if object_to_search.classID == 1: #table 00327 verified_table = self.eo.verify_table(userdata.target_table_pose, object_list_map) 00328 #verified_table = object_list_map.objects.shapes[2] 00329 if verified_table: 00330 hull = verified_table.points[0] 00331 #print verified_table.params 00332 #print "table " + str(userdata.target_object_pose.position.x) + "," + str(userdata.target_object_pose.position.y) + " found at " + str(verified_table.params[4]) + "," + str(verified_table.params[5]) 00333 else: 00334 print "table " + str(userdata.target_table_pose.position.x) + "," + str(userdata.target_table_pose.position.y) + " not found" 00335 return 'not_completed' 00336 goal = TableObjectClusterGoal(hull) 00337 if not self.client.wait_for_server():#rospy.Duration.from_sec(5.0)): 00338 rospy.logerr('server not available') 00339 return 'not_completed' 00340 self.client.send_goal(goal) 00341 if not self.client.wait_for_result():#rospy.Duration.from_sec(5.0)): 00342 return 'not_completed' 00343 userdata.object_cluster = self.client.get_result().bounding_boxes 00344 return 'succeeded' 00345 00346 00347 """Checks, whether target_object_pose_on_table is occupied by at least one object of object_cluster. 00348 Returns succeded if the position is free and failed if the position is occupied""" 00349 class CheckPoseOnTableFree(smach.State): 00350 00351 def __init__(self): 00352 00353 smach.State.__init__( 00354 self, 00355 outcomes=['succeeded', 'failed', 'not_completed', 'preempted'], 00356 input_keys=['target_object_pose_on_table','object_cluster'], 00357 output_keys=[]) 00358 00359 def execute(self, userdata): 00360 for bb in userdata.object_cluster: 00361 pt1 = [] 00362 for i in range(0,3): 00363 pt1.append(unpack("f",bb.data[4*i:4*i+4])[0]) 00364 pt2 = [] 00365 for i in range(4,7): 00366 pt2.append(unpack("f",bb.data[4*i:4*i+4])[0]) 00367 x = userdata.target_object_pose_on_table.position.x 00368 y = userdata.target_object_pose_on_table.position.y 00369 if x>pt1[0] and x<pt2[0] and y>pt1[1] and y<pt2[1]: 00370 print "target position occupied" 00371 return 'failed' 00372 else: 00373 print "target position free" 00374 return 'succeeded' 00375