Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
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
00027
00028
00029
00030 from random import choice
00031
00032 foo = ['table2', 'table1','fridge']
00033
00034 historical_data_LW=[]
00035
00036
00037
00038 action_sequences_global=[]
00039
00040 task_flag=""
00041
00042
00043
00044
00045
00046
00047 def data_from_learning_window(learning_window_width,historical_full_path):
00048
00049 line_offset = []
00050 historical_data_LW=[]
00051
00052 num_lines=0
00053 offset = 0
00054
00055 fo=open(historical_full_path,'r')#open the historical_data
00056
00057
00058 for line in fo:
00059 line_offset.append(offset)
00060 offset += len(line)
00061 num_lines+=1
00062
00063
00064
00065 if num_lines>=learning_window_width:
00066
00067 n=num_lines-learning_window_width
00068 else:
00069 n=0
00070
00071
00072 fo.seek(line_offset[n])
00073
00074
00075 for line in fo:
00076
00077
00078 if line[-1] == '\n':
00079 line1=line[:-1]
00080 else:
00081 line1=line
00082 historical_data_LW.append(line1)
00083
00084
00085 fo.close()
00086 return historical_data_LW
00087
00088 def calculate_likelihood(data_for_likelihood,candidate_list):
00089
00090 candidates_list=candidate_list.split()
00091
00092 candidate_frenquence={}
00093 candidate_weight={}
00094 candidate_likelihood={}
00095 initial_weight=0.1
00096
00097 for candi in candidates_list:
00098 candidate_frenquence[candi]=0
00099 candidate_weight[candi]=0
00100 candidate_likelihood[candi]=0
00101
00102 for action in data_for_likelihood:
00103
00104 if action.find('place_on_tray'):
00105
00106
00107
00108 location_flag=action.rfind('move(base,')
00109 sub_actions=action[location_flag:]
00110 sub_actions_list=sub_actions.split(', ')
00111 print "the location is in %s"%sub_actions_list[0]
00112
00113
00114
00115 for candidate in candidates_list:
00116
00117 if sub_actions_list[0].find(','+candidate+')')>0:
00118
00119 print "the location is %s"%candidate
00120 candidate_frenquence[candidate]+=1/10.0
00121 print "the candidate_frenquence for %s is %s" %(candidate,candidate_frenquence[candidate])
00122 candidate_weight[candidate]+=initial_weight/5.5
00123 print "the candidate_weight for %s is %s" %(candidate,candidate_weight[candidate])
00124 candidate_likelihood[candidate]=(candidate_frenquence[candidate]+candidate_weight[candidate])/2.0
00125
00126 print "the candidate_likelihood for %s is %s" %(candidate,candidate_likelihood[candidate])
00127 initial_weight+=0.1
00128
00129
00130 else:
00131
00132
00133
00134
00135 initial_weight+=0.1
00136
00137
00138
00139
00140
00141 print "candidate_frenquence is: %s" %candidate_frenquence
00142 print "candidate_weight is: %s" %candidate_weight
00143 print "candidate_likelihood is %s" %candidate_likelihood
00144 candidate_likelihood_list=candidate_likelihood.items()
00145 return str(candidate_likelihood_list)
00146
00147
00148
00149 def handle_consulting(req):
00150
00151
00152
00153
00154 print "consulting command is: %s "%req.command
00155 print "consulting candidates are: %s" %req.candidate
00156
00157
00158
00159 data_for_likelihood=data_from_learning_window(10,'historical_data.txt')
00160 print"the historical_data based on learning_window_width=10 is: "
00161 print data_for_likelihood
00162 print "the number of historical_data is %d"%len(data_for_likelihood)
00163
00164
00165 likelihoodresponse=calculate_likelihood(data_for_likelihood,req.candidate)
00166 return LikelihoodResponse(likelihoodresponse)
00167
00168
00169
00170
00171 def find_ralation(actions,results,objects):
00172
00173
00174 on_something={}
00175 on_something['move']='3'
00176 on_something['detect']='3'
00177 on_something['grasp']='3'
00178 on_something['place_on_tray']='3'
00179
00180
00181 in_something={}
00182 in_something['move']='3'
00183 in_something['open']='3'
00184 in_something['detect']='3'
00185 in_something['grasp']='3'
00186 in_something['place_on_tray']='3'
00187 in_something['close']='3'
00188
00189 action_list=actions.split()
00190 print action_list
00191 result_list=results.split()
00192 print result_list
00193
00194 actions_result={}
00195 for action in action_list:
00196 actions_result[action]=result_list[int(action_list.index(action))]
00197
00198
00199
00200
00201 for action in action_list:
00202
00203 print action
00204
00205 if action.find('detect')>=0:
00206
00207 print 'detect action is found!'
00208
00209
00210 if actions_result[action]=='3':
00211
00212
00213 print 'detect action is successful!'
00214 if actions.rfind('open')>=0:
00215 for action1 in action_list:
00216 if action1.find('open')>=0:
00217 print 'is open'
00218
00219
00220 if actions_result[action1]=='3':
00221 return 'in_something'
00222 else:
00223 print 'unknown relationship'
00224 return 'unknow relationship'
00225
00226 elif actions.rfind('move')>=0:
00227 for action1 in action_list:
00228 if action1.find('move')>=0:
00229 print 'is move'
00230 if actions_result[action1]=='3':
00231 return 'on_something'
00232 else:
00233 print 'unknown relationship'
00234 return 'unknow relationship'
00235 else:
00236 print 'unknown relationship'
00237 return 'unknow relationship'
00238 else:
00239 print 'detect action is failed, can not detect object!'
00240 return 'can not detect object!'
00241
00242
00243
00244 def handle_consulting2(req):
00245
00246
00247
00248
00249 print "consulting command is: %s "%req.command
00250 print "consulting actions are: %s" %req.actions
00251 print "consulting actions results are: %s" %req.results
00252 if req.objects!="":
00253 print "consulting objects are: %s" %req.objects
00254
00255
00256
00257
00258 ontologyresponse=find_ralation(req.actions,req.results,req.objects)
00259
00260
00261 return OntologyResponse(ontologyresponse)
00262
00263 def callback_record_data(data):
00264
00265
00266
00267 print "task instance result is:",data.result
00268 global action_sequences_global
00269
00270
00271 if data.result==' return_value: 3':
00272 print "Task successfully finished\n"
00273 task_action_sequence=','.join(action_sequences_global)
00274 fo = open("dynamic_historical_data.txt", "ab")
00275 fo.write( task_action_sequence +"\n");
00276 action_sequences_global=[]
00277
00278
00279 fo.close()
00280
00281
00282 def historical_data_recorder(data):
00283
00284 global action_sequences_global
00285
00286 print "action_sequences_global is %s" %action_sequences_global
00287
00288 feedback_temp=str(data)
00289
00290 location_flag_jsonfeedback=feedback_temp.find('json_feedback:')
00291 sub_feedback_temp=feedback_temp[location_flag_jsonfeedback+len('json_feedback:'):]
00292 if sub_feedback_temp.find('name')>0:
00293 print "sub_feedback_temp is: %s" %sub_feedback_temp
00294
00295 feedback_dict=json.loads(sub_feedback_temp)
00296
00297
00298
00299
00300
00301
00302
00303 feedback_dict1=json.loads(feedback_dict)
00304
00305
00306
00307 actions_doing=feedback_dict1["current_action"]
00308
00309 task_info=feedback_dict1["task"]
00310
00311 task_flag_temp=task_info["task_id"]
00312
00313
00314 if actions_doing["state"]=='succeeded':
00315
00316 actionis=actions_doing["name"]
00317 action_with_para_li=[actionis]
00318
00319
00320
00321 action_target=actions_doing["target_object"]
00322
00323 action_with_para_li.append(action_target)
00324
00325 action_with_para_str=' '.join(action_with_para_li)
00326
00327 print "curret action is: %s" %action_with_para_str
00328
00329
00330
00331
00332 if action_sequences_global==[]:
00333 action_sequences_global=[action_with_para_str]
00334 print "action %s is recorded into historical data\n" %action_with_para_str
00335 print "the first action_sequences_global is %s" %action_sequences_global
00336
00337
00338 else:
00339 print "the non_null action_sequences_global list is %s" %action_sequences_global
00340
00341 action_sequences_global.append(action_with_para_str)
00342 print "action %s is recorded into historical data\n" %action_with_para_str
00343
00344
00345
00346 fo = open("dict_dynamic_feedback_DM_historical_data.txt", "ab")
00347 fo.write(action_with_para_str+"\n")
00348 fo.close()
00349
00350 else:
00351 print 'This is init state'
00352
00353
00354
00355 def callback_record_data2(data):
00356
00357 temp_feed= data.feedback
00358
00359
00360
00361 task_actions=temp_feed
00362
00363 historical_data_recorder(task_actions)
00364
00365 def consulting_server():
00366
00367 rospy.init_node('likelyhood_server', anonymous=True)
00368
00369 rospy.Subscriber("srs_decision_making_actions/feedback", ExecutionActionFeedback, callback_record_data2)
00370 rospy.Subscriber("srs_decision_making_actions/result", ExecutionActionResult, callback_record_data)
00371
00372 rospy.Service('likelihood', Likelihood, handle_consulting)
00373 rospy.Service('ontology', Ontology, handle_consulting2)
00374 print "Ready to receive consulting."
00375 rospy.spin()
00376
00377 if __name__ == "__main__":
00378
00379 consulting_server()
00380