$search
00001 #!/usr/bin/env python 00002 ################################################################# 00003 # \note historical_data record subscriber 00004 # \input(from DEM to learning) command and candidates 00005 # \output(from learning to DEM) candidate and correspomding likelihood 00006 # Project name: srs learning service for choosing priority 00007 # \author 00008 # Tao Cao, email:itaocao@gmail.com 00009 # 00010 # \date Date of creation: Dec 2011 00011 ################################################################# 00012 00013 import roslib; roslib.load_manifest('srs_likelihood_calculation') 00014 00015 from srs_likelihood_calculation.srv import * 00016 00017 from std_msgs.msg import String 00018 import rospy 00019 00020 import actionlib 00021 00022 from srs_decision_making.msg import * 00023 00024 import fileinput 00025 00026 import json # or `import simplejson as json` if on Python < 2.6 00027 00028 #randomly generate the location 00029 00030 from random import choice 00031 00032 foo = ['table2', 'table1','fridge'] 00033 00034 fake_data=[ 00035 "move(base,table1), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00036 "move(base,fridge), detect(milkbox), move(base,table1), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00037 "move(base,table1), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00038 "move(base,fridge), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00039 "move(base,table2), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00040 "move(base,table1), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00041 "move(base,table1), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00042 "move(base,fridge), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00043 "move(base,table1), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00044 "move(base,table2), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)" 00045 ] 00046 00047 fake_data1=[ 00048 "move(base,table1), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00049 "move(base,fridge), detect(milkbox), move(base,table1), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00050 "move(base,table1), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00051 "move(base,table2), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00052 "move(base,fridge), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00053 "move(base,fridge), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00054 "move(base,table2), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00055 "move(base,table1), detect(milkbox), move(base,table1), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00056 "move(base,table1), detect(milkbox), move(base,table2), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)", 00057 "move(base,fridge), detect(milkbox), move(base,fridge), detect(milkbox), grasp(Milk box), place_on_tray(Milk box)" 00058 ] 00059 00060 historical_data_LW=[] 00061 00062 #global action_sequences_global 00063 00064 action_sequences_global=[]# action sequence for taks instance 00065 00066 task_flag="" 00067 00068 #using learning window to read historical data 00069 #this function will be updated 00070 #the learning_window_width will be decided based on the learning experience 00071 #this function should only need the historical_data file name, and will search this file itself 00072 00073 def data_from_learning_window(learning_window_width,historical_full_path): 00074 #learning_window_width=learning_window_width 00075 line_offset = [] 00076 historical_data_LW=[] 00077 00078 num_lines=0 #the number of lines of the historical_data(how big the experience is) 00079 offset = 0 #the offset for a line 00080 00081 fo=open(historical_full_path,'r')#open the historical_data 00082 00083 #calculate the num_lines and the offset for every line 00084 for line in fo: 00085 line_offset.append(offset) 00086 offset += len(line) 00087 num_lines+=1 00088 #file.seek(0) # reset offset to the begining of the file 00089 #n+learning_window_width=num_lines 00090 #the n is the line number, so n >=0, this means, num_lines>=learning_window_width, the program should make sure this is true 00091 if num_lines>=learning_window_width: 00092 #learning according the learning_window_width 00093 n=num_lines-learning_window_width 00094 else: 00095 n=0 #using the whole historical_data 00096 00097 # Now, to skip to line n (with the first line being line 0), just do 00098 fo.seek(line_offset[n]) 00099 00100 00101 for line in fo: 00102 00103 #remove the end-line character from the action sequence 00104 if line[-1] == '\n': 00105 line1=line[:-1] 00106 else: 00107 line1=line 00108 historical_data_LW.append(line1) 00109 00110 # Close opend file 00111 fo.close() 00112 return historical_data_LW #return the historical_data list based on the learning_window_width 00113 00114 def calculate_likelihood(data_for_likelihood,candidate_list): 00115 #task_success_flag=[]#flag to mark the task is sucessful or not 00116 candidates_list=candidate_list.split()#store all the candidates into a list 00117 #set up a dict structure to save candidates and correspomding frenquency 00118 candidate_frenquence={} 00119 candidate_weight={} 00120 candidate_likelihood={} 00121 initial_weight=0.1#in this stage, the weight is from 0.1,0.2,..., 1, totally 10 weights 00122 #the initial frequence and weight is 0 00123 for candi in candidates_list: 00124 candidate_frenquence[candi]=0 00125 candidate_weight[candi]=0 00126 candidate_likelihood[candi]=0 00127 00128 for action in data_for_likelihood:#data_for_likelihood is a list, with action sequence as items 00129 # action in data_for_likelihood list is a string, which has the find method 00130 if action.find('place_on_tray'): 00131 #find the action marker, the task is sucessful 00132 #task_success_flag.append(1) this task_success_flag is not needed 00133 #find the nearest move(base,position) action to match the candidates 00134 location_flag=action.rfind('move(base,')# mark where is the location for grasp 00135 sub_actions=action[location_flag:]#sub action sequence begining with move action 00136 sub_actions_list=sub_actions.split(', ')#the delimiter is', ', this delimiter will split action sequence into action list 00137 print "the location is in %s"%sub_actions_list[0] 00138 #check which candidate is the location 00139 #comparing the candidates in candidates_list with the current loation 00140 00141 for candidate in candidates_list:#choosing candidates from dict candidate_frenquence 00142 00143 if sub_actions_list[0].find(','+candidate+')')>0:#the candidate is the location, correspomding frequence and weight will be updated 00144 #sub_actions_list[0].find(','+candidate+')') make sure the candidate can be exactly matched 00145 print "the location is %s"%candidate 00146 candidate_frenquence[candidate]+=1/10.0#10.0 is the totally number of historical_data 00147 print "the candidate_frenquence for %s is %s" %(candidate,candidate_frenquence[candidate]) 00148 candidate_weight[candidate]+=initial_weight/5.5#5.5=(0.1+0.2+...+1) 00149 print "the candidate_weight for %s is %s" %(candidate,candidate_weight[candidate]) 00150 candidate_likelihood[candidate]=(candidate_frenquence[candidate]+candidate_weight[candidate])/2.0 00151 #candidate_likelihood[candidate]+=candidate_frenquence[candidate]+candidate_weight[candidate] 00152 print "the candidate_likelihood for %s is %s" %(candidate,candidate_likelihood[candidate]) 00153 initial_weight+=0.1 00154 00155 00156 else: 00157 #we assumed all action sequences for a task is successful in this stage, this else here is to handle exceptions of receiving failed tasks 00158 #without the action marker,the task is failed 00159 #there will be no frenquecy and weight for any candidate 00160 #task_success.append(0) 00161 initial_weight+=0.1 00162 # 00163 #after above for loop, all the historical_data_LW had been used for calculating frenquence and weight 00164 #now use the frenquence and weight to calculate the likelihood 00165 # 00166 #likelihood=(weight+frenquence)/2 this also can be done in the for loop as shown above 00167 print "candidate_frenquence is: %s" %candidate_frenquence 00168 print "candidate_weight is: %s" %candidate_weight 00169 print "candidate_likelihood is %s" %candidate_likelihood 00170 candidate_likelihood_list=candidate_likelihood.items() 00171 return str(candidate_likelihood_list) 00172 00173 00174 # callback function for receive consulting command and candidates 00175 def handle_consulting(req): 00176 #req is the consulting information command+candidates from the DEM to Learning_service 00177 #both the command and candidates will be used for likelihood calculating based on the historical data of learning 00178 #command used for task classification 00179 #cadidates used for activity cluster 00180 print "consulting command is: %s "%req.command 00181 print "consulting candidates are: %s" %req.candidate 00182 #here we just read the historical_data from the txt file 00183 #the final data should come from a search based on the command (task classification) and candidates(for activity cluster) 00184 #!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! 00185 #data_for_likelihood=data_from_learning_window(10,'historical_data.txt') 00186 data_for_likelihood=fake_data1 00187 00188 print"the historical_data based on learning_window_width=10 is: " 00189 print data_for_likelihood 00190 print "the number of historical_data is %d"%len(data_for_likelihood) 00191 #calculating the likelihood 00192 #likelihoodresponse="likelihood for %s from %s is ??? "%(req.command,req.candidate) 00193 likelihoodresponse=calculate_likelihood(data_for_likelihood,req.candidate) 00194 return LikelihoodResponse(likelihoodresponse) 00195 00196 00197 #definition of the find_ralation function 00198 00199 def find_ralation(actions,results,objects): 00200 00201 #define the on relationship 00202 on_something={} 00203 on_something['move']='3' 00204 on_something['detect']='3' 00205 on_something['grasp']='3' 00206 on_something['place_on_tray']='3' 00207 00208 #define the in relationship 00209 in_something={} 00210 in_something['move']='3' 00211 in_something['open']='3' 00212 in_something['detect']='3' 00213 in_something['grasp']='3' 00214 in_something['place_on_tray']='3' 00215 in_something['close']='3' 00216 00217 action_list=actions.split() 00218 print action_list 00219 result_list=results.split() 00220 print result_list 00221 # build up the action_result dictionary to use the results of actions 00222 actions_result={} 00223 for action in action_list: 00224 actions_result[action]=result_list[int(action_list.index(action))] 00225 #print 'actions_result is: ',actions_result.items() 00226 #return str(actions_result) 00227 #print 'actions_result.keys()',actions_result.keys() 00228 00229 for action in action_list: 00230 #for relationship detect action is the marker of the relationship 00231 print action 00232 00233 if action.find('detect')>=0: 00234 00235 print 'detect action is found!' 00236 #find the action mark 00237 #then check the detect action successful or not 00238 if actions_result[action]=='3': 00239 #detect action is successful 00240 #then find the open action 00241 print 'detect action is successful!' 00242 if actions.rfind('open')>=0: 00243 for action1 in action_list: 00244 if action1.find('open')>=0: 00245 print 'is open' 00246 #find the open action 00247 #then check the open is successful 00248 if actions_result[action1]=='3': 00249 return 'in_something' 00250 else: 00251 print 'unknown relationship' 00252 return 'unknow relationship' 00253 00254 elif actions.rfind('move')>=0: 00255 for action1 in action_list: 00256 if action1.find('move')>=0: 00257 print 'is move' 00258 if actions_result[action1]=='3': 00259 return 'on_something' 00260 else: 00261 print 'unknown relationship' 00262 return 'unknow relationship' 00263 else: 00264 print 'unknown relationship' 00265 return 'unknow relationship' 00266 else: 00267 print 'detect action is failed, can not detect object!' 00268 return 'can not detect object!' 00269 00270 00271 # callback function for receive consulting for ontology expanding 00272 def handle_consulting2(req): 00273 #req is the consulting information command+candidates from the DEM to Learning_service 00274 #both the command and candidates will be used for likelihood calculating based on the historical data of learning 00275 #command used for task classification 00276 #cadidates used for activity cluster 00277 print "consulting command is: %s "%req.command 00278 print "consulting actions are: %s" %req.actions 00279 print "consulting actions results are: %s" %req.results 00280 if req.objects!="": 00281 print "consulting objects are: %s" %req.objects 00282 #else: 00283 #find objects from the commands 00284 00285 00286 ontologyresponse=find_ralation(req.actions,req.results,req.objects) 00287 #ontologyresponse="ontology for %s is ??? "%req.objects 00288 00289 return OntologyResponse(ontologyresponse) 00290 00291 def callback_record_data(data): 00292 00293 #rospy.loginfo(rospy.get_name()+"Action sequence is: %s",data.data) 00294 #print rospy.get_name()+" Action sequence is: ",data.data 00295 print "task instance result is:",data.result 00296 global action_sequences_global 00297 # Open a file 00298 #action_sequences=action_sequences_global 00299 if data.result==' return_value: 3':#task successfully executed return_value: 3 00300 print "Task successfully finished\n" 00301 task_action_sequence=','.join(action_sequences_global) 00302 fo = open("dynamic_historical_data.txt", "ab") 00303 fo.write( task_action_sequence +"\n"); 00304 action_sequences_global=[] 00305 00306 # Close opend file 00307 fo.close() 00308 00309 00310 def historical_data_recorder(data): #publish the data 00311 #print "Json feedback is: ",data 00312 global action_sequences_global 00313 00314 print "action_sequences_global is %s" %action_sequences_global 00315 00316 feedback_temp=str(data) 00317 00318 location_flag_jsonfeedback=feedback_temp.find('json_feedback:')# mark where is the location for grasp 00319 sub_feedback_temp=feedback_temp[location_flag_jsonfeedback+len('json_feedback:'):]#sub action sequence begining with move action 00320 if sub_feedback_temp.find('name')>0: 00321 print "sub_feedback_temp is: %s" %sub_feedback_temp 00322 00323 feedback_dict=json.loads(sub_feedback_temp) #type of feedback_dict: <type 'unicode'> 00324 00325 00326 00327 #print "feedback_dict is: %s" %feedback_dict 00328 00329 #print "type of feedback_dict: %s" %type(feedback_dict) 00330 00331 feedback_dict1=json.loads(feedback_dict)#type of feedback_dict1: <type 'dict'> 00332 00333 #print "type of feedback_dict1: %s" %type(feedback_dict1) 00334 00335 actions_doing=feedback_dict1["current_action"] 00336 00337 task_info=feedback_dict1["task"] 00338 00339 task_flag_temp=task_info["task_id"] 00340 00341 00342 if actions_doing["state"]=='succeeded': # only record the successful actions 00343 00344 actionis=actions_doing["name"]#get the action 00345 action_with_para_li=[actionis] 00346 ## get the action target 00347 00348 #action_with_para_li.append(actions_doing["target"]) 00349 action_target=actions_doing["target_object"] 00350 00351 action_with_para_li.append(action_target) 00352 00353 action_with_para_str=' '.join(action_with_para_li) 00354 00355 print "curret action is: %s" %action_with_para_str 00356 00357 ### this action_sequences is used as a stack for storing action sequence of a task instance 00358 ## the following two lines update action_sequences 00359 00360 if action_sequences_global==[]:#this action_sequences is null 00361 action_sequences_global=[action_with_para_str] 00362 print "action %s is recorded into historical data\n" %action_with_para_str 00363 print "the first action_sequences_global is %s" %action_sequences_global 00364 #action_sequences_global = action_sequences 00365 00366 else: 00367 print "the non_null action_sequences_global list is %s" %action_sequences_global 00368 #####action_sequences_global=action_sequences_global.append(action_with_para_str)#update action sequence 00369 action_sequences_global.append(action_with_para_str)#update action sequence 00370 print "action %s is recorded into historical data\n" %action_with_para_str 00371 #action_sequences_global = action_sequences 00372 00373 # Open a file 00374 fo = open("dict_dynamic_feedback_DM_historical_data.txt", "ab") 00375 fo.write(action_with_para_str+"\n") 00376 fo.close() 00377 00378 else: 00379 print 'This is init state' 00380 00381 00382 00383 def callback_record_data2(data): 00384 00385 temp_feed= data.feedback 00386 00387 00388 00389 task_actions=temp_feed 00390 00391 historical_data_recorder(task_actions) 00392 00393 def consulting_server(): 00394 00395 rospy.init_node('likelyhood_server', anonymous=True) 00396 00397 rospy.Subscriber("srs_decision_making_actions/feedback", ExecutionActionFeedback, callback_record_data2) #record the historical data 00398 rospy.Subscriber("srs_decision_making_actions/result", ExecutionActionResult, callback_record_data) #record the historical data 00399 00400 rospy.Service('likelihood', Likelihood, handle_consulting) #provide service 00401 rospy.Service('ontology', Ontology, handle_consulting2) #provide service 00402 print "Ready to receive consulting." 00403 rospy.spin() 00404 00405 if __name__ == "__main__": 00406 00407 consulting_server() 00408