take_human_input.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 import time
00004 import rospy
00005 
00006 import roslib; roslib.load_manifest('bwi_tasks')
00007 
00008 import actionlib
00009 import actionlib_msgs.msg
00010 from bwi_kr_execution.msg import *
00011 from bwi_msgs.srv import QuestionDialog, SemanticParser
00012 import os.path
00013 import string
00014 
00015 from bwi_scavenger.srv import *
00016 
00017 from multiprocessing import Process, Value, Array
00018 
00019 from PIL import Image
00020 import subprocess
00021 
00022 log = ''
00023 finished = False
00024 
00025 person_door = {'peter'      : 'd3_508', 
00026                'dana'       : 'd3_510',
00027                'ray'        : 'd3_512',
00028                'raymond'    : 'd3_512',
00029                'stacy'      : 'd3_502',
00030                'kazunori'   : 'd3_402',
00031                'matteo'     : 'd3_418',
00032                'jivko'      : 'd3_432',
00033                'shiqi'      : 'd3_420',
00034                'piyush'     : 'd3_416',
00035                'daniel'     : 'd3_436'}
00036 
00037 room_list = ['l3_502', 'l3_504', 'l3_508', 'l3_510', 'l3_512', 'l3_516',
00038              'l3_436', 'l3_402', 'l3_404', 'l3_416', 'l3_418', 'l3_420',
00039              'l3_422', 'l3_430', 'l3_432', 'l3_414a', 'l3_414b']
00040 
00041 door_list = ['d3_502', 'd3_504', 'd3_508', 'd3_510', 'd3_512', 'd3_516',
00042              'd3_436', 'd3_402', 'd3_404', 'd3_416', 'd3_418', 'd3_420',
00043              'd3_422', 'd3_430', 'd3_432', 'd3_414a1', 'd3_414a2', 'd3_414b1',
00044              'd3_414b2']
00045 
00046 resting_time = 5
00047 cnt = 0
00048 last_loc = ''
00049 
00050 def task_guiding(doorname, client, dialog_handle):
00051 
00052     global log
00053     roomname = doorname[doorname.find('_')+1 : ]
00054     
00055     if roomname.find('414') >= 0:
00056         roomname = roomname[:-1]
00057 
00058     roomname = '3.' + roomname
00059 
00060     dialog_handle(0, "I am going to " + roomname + '. ', [], 0)
00061 
00062 
00063     goal = ExecutePlanGoal()
00064     rule = AspRule()
00065     fluent = AspFluent()
00066     
00067     fluent.name = "not facing"
00068     fluent.variables = [doorname]
00069     rule.body = [fluent]
00070     goal.aspGoal = [rule]
00071     
00072     rospy.loginfo("Sending goal (doorname): " + doorname)
00073     client.send_goal(goal)
00074     client.wait_for_result()
00075 
00076     log += "guiding: " + roomname
00077     finished = True
00078 
00079 def task_delivery(person, item, client, dialog_handle):
00080 
00081     global log
00082     global person_door
00083 
00084     upper_person = person[0].upper() + person[1:]
00085     dialog_handle(0, "I am going to pick up " + item + " for " + \
00086                   upper_person + '. ', [], 0)
00087 
00088 
00089     goal = ExecutePlanGoal()
00090     rule = AspRule()
00091     fluent = AspFluent()
00092     
00093     # going to the shop first - there is no shop - going to the kitchen: 520
00094     fluent.name = "not facing"
00095     fluent.variables = ["d3_520"]
00096     rule.body = [fluent]
00097     goal.aspGoal = [rule]
00098     
00099     rospy.loginfo("Sending goal (doorname): " + fluent.variables[0])
00100     client.send_goal(goal)
00101 
00102     client.wait_for_result()
00103 
00104     res = dialog_handle(1, "May I have " + item + " please?", \
00105                  ["Sorry, we do not have that", "Loaded"], 60)
00106 
00107     hasLoaded = (res.index == 1)
00108     
00109     if res.index == 1:
00110         res = dialog_handle(0, "I am taking " + item + " to " + upper_person + \
00111                         ". ", [""], 0)
00112     else:
00113         res = dialog_handle(0, "I am going to tell " + upper_person + \
00114                             " that " + item + " is not available. ", [""], 0)
00115 
00116     fluent.name = "not facing"
00117     fluent.variables = [person_door[person]]
00118     rule.body = [fluent]
00119     goal.aspGoal = [rule]
00120     
00121     # loaded item, now going to the person's place
00122 
00123     rospy.loginfo("Sending goal (doorname): " + person_door[person])
00124     client.send_goal(goal)
00125     client.wait_for_result()
00126 
00127     if hasLoaded == True:
00128         res = dialog_handle(1, "Someone requested this " + item + \
00129                             " to be delivered to you. Please take it. ", \
00130                             ["Unloaded"], 60)
00131     else:
00132         res = dialog_handle(1, "Someone requested " + item + \
00133                             " be delivered to you, but the store did not give it to me. ", \
00134                             ["I see."], 60)
00135 
00136     log += "delivery: " + item + ' ' + upper_person
00137     finished = True
00138 
00139 def process_request(query, client, dialog_handle):
00140 
00141     global room_list    
00142     global door_list   
00143     global person_door
00144 
00145     rospy.loginfo("query: " + query)
00146 
00147     if (query.find("at(") >= 0): # this is a guiding task! 
00148 
00149         room = query[query.find('l') : query.find(',')]
00150 
00151         if room in room_list:
00152 
00153             query = query.replace("at(l", "d")
00154             query = query[:query.find(",")]
00155 
00156             # in case there are multiple doors to a room, select the first one
00157             if query.find("d3_414") > 0:
00158                 query += "1"
00159 
00160             task_guiding(query, client, dialog_handle)
00161 
00162         else:
00163 
00164             rospy.logwarn("This does not seem to be a room name: " + room)
00165 
00166     elif (query.find("query(") >= 0): # this is a question-asking task! 
00167 
00168         rospy.logwarn("Query from semantic parser: " + query)
00169         # query = query.replace("query(l", "d")
00170         # query = query[:query.find(":")]
00171 
00172         # if query.find("d3_414") > 0:
00173         #     query += "1"
00174 
00175         # task_guiding(query, client, dialog_handle)
00176 
00177         return False
00178 
00179     elif (query.find("served(") >= 0): # this is a delivery task! 
00180 
00181         # served(shiqi,coffee,n)
00182 
00183         person = query[query.find('(')+1 : query.find(',')]
00184 
00185         if person in person_door: 
00186 
00187             # remove the person name -> coffee,n)
00188             query = query[query.find(',')+1 : ]
00189             item = query[: query.find(',')]
00190 
00191             task_delivery(person, item, client, dialog_handle)
00192 
00193         else:
00194 
00195             rospy.logwarn("This does not seem to be a person name: " + person)
00196 
00197     return True
00198 
00199 # option
00200 # 1: click me if you need help
00201 # 2: please let me know your goal place
00202 def gui_thread(human_waiting, curr_goal):
00203 
00204     rospy.init_node('human_input_gui_thread')
00205     rospy.loginfo("gui_thread started")
00206     rospy.wait_for_service('question_dialog')
00207     handle = rospy.ServiceProxy('question_dialog', QuestionDialog)
00208 
00209     while not rospy.is_shutdown():
00210 
00211         if finished == True:
00212             return True
00213 
00214         if human_waiting.value == True:
00215             rospy.sleep(2)
00216             continue
00217 
00218         res = handle(1, "", ["Button"], 2)
00219 
00220         while (res.index < 0):
00221 
00222             if len(curr_goal.value) > 6:
00223                 g = "3." + curr_goal.value[3:-1]
00224             else:
00225                 g = "3." + curr_goal.value[3:]
00226 
00227             res = handle(1, "Please click the button, if you need my help." + \
00228                          "\n\nI am moving to room " + g, ["Button"], 0)
00229 
00230         human_waiting.value = True
00231 
00232     return True
00233 
00234 def platform_thread(human_waiting, curr_goal):
00235 
00236     global cnt
00237     global resting_time
00238     global last_loc
00239 
00240     rospy.init_node('human_input_platform_thread')
00241     rospy.loginfo("platform_thread started")
00242 
00243     rospy.wait_for_service('question_dialog')
00244     dialog_handle = rospy.ServiceProxy('question_dialog', QuestionDialog)
00245 
00246     rospy.wait_for_service('semantic_parser')
00247     parser_handle = rospy.ServiceProxy('semantic_parser', SemanticParser)
00248 
00249     client = actionlib.SimpleActionClient('/action_executor/execute_plan',
00250                                           ExecutePlanAction)
00251     client.wait_for_server()
00252 
00253     rooms = ["414a", "414b", "414b", "418", "420"]
00254     doors = ["d3_414a2", "d3_414b1", "d3_414b2", "d3_418", "d3_420"]
00255 
00256     path_rlg = rospy.get_param("/semantic_parser_server/path_to_bwi_rlg")
00257     filepath = path_rlg + "/agent/dialog/list_of_bad_data.txt"
00258 
00259     while not rospy.is_shutdown():
00260 
00261         if finished == True:
00262             return True
00263 
00264         if human_waiting.value == True:
00265 
00266             # a human may give goals to the robot one after another
00267             while True:
00268 
00269                 # commumication......
00270                 # robot speaks first
00271 
00272                 res_qd = dialog_handle(0, \
00273                          'At this time, I can only help with navigation and item delivery to named people. Please try not to change your mind about what you want while we chat. ', \
00274                          [""], 5)
00275                 rospy.sleep(6)
00276 
00277                 # img = subprocess.Popen(["eog", \
00278                 #                       path_rlg + '/images/unnamed.jpg'])
00279 
00280                 res_sp = parser_handle(0, "STARTING-KEYWORD")
00281 
00282                 while len(res_sp.query) == 0 and res_qd.index != -2:
00283                     
00284                     # take human feedback
00285                     res_qd = dialog_handle(2, res_sp.output_text, doors, 60)
00286 
00287                     # robot speaks back
00288                     res_sp = parser_handle(0, res_qd.text)
00289 
00290                     # the robot prints: I am thinking...
00291                     dialog_handle(0, "I am thinking...", doors, 2)
00292                     rospy.sleep(2)
00293 
00294                 # now the robot has found the query from semantic parser
00295 
00296                 hasSucceeded = process_request(res_sp.query, \
00297                                                client, dialog_handle)
00298                 
00299                 # img.kill()
00300                 # identify good (and bad) data
00301                 res = dialog_handle(1, "Did I accomplish the goal you were trying to convey?", \
00302                                     ["Yes", "No"], 60)
00303 
00304                 # if no response, assuming it's a wrong one
00305                 if res.index == 0:
00306 
00307                     # incrementally learning
00308                     dialog_handle(0, "I am learning...", doors, 10)
00309                     subprocess.call("python " + path_rlg +\
00310                                     "/agent/dialog/main.py " +\
00311                                      path_rlg + "/agent/dialog/ " +\
00312                                      "retrain -exclude_test_goals", shell=True)
00313 
00314                 else:
00315 
00316                     if os.path.exists(filepath):
00317                         f = open(filepath, 'a')
00318                     else:
00319                         f = open(filepath, 'w+')
00320 
00321                     res_sp = parser_handle(3, res_qd.text)
00322                     f.write(res_sp.output_text + '---' + res_sp.query + '\n')
00323                     f.close()
00324 
00325                 # anything else for the same user? 
00326                 res = dialog_handle(1, "Do you need anything else?", \
00327                                     ["Yes", "No"], 15)
00328 
00329                 if res.index < 0 or res.index == 1:
00330 
00331                     human_waiting.value = False
00332                     break
00333 
00334         else:
00335 
00336             rospy.loginfo("No one needs me. I will do a random walk.")
00337             rospy.sleep(1)
00338 
00339             if (cnt % resting_time) == 0 or last_loc == '': 
00340 
00341                 loc = doors[int(time.time()) % len(rooms)]
00342                 last_loc = loc
00343 
00344             else:
00345 
00346                 loc = last_loc
00347 
00348             cnt += 1
00349 
00350             curr_goal.value = loc
00351             goal = ExecutePlanGoal()
00352             rule = AspRule()
00353             fluent = AspFluent()
00354             
00355             fluent.name = "not beside"
00356             fluent.variables = [loc]
00357             rule.body = [fluent]
00358             goal.aspGoal = [rule]
00359             
00360             rospy.loginfo("sending goal: " + loc)
00361             client.send_goal(goal)
00362             
00363             while client.wait_for_result(
00364                     timeout = rospy.Duration.from_sec(1.0)) == False:
00365                 if human_waiting.value:
00366                     break
00367 
00368             client.cancel_goal()
00369 
00370             move_base_pub = rospy.Publisher('move_base/cancel',\
00371                                             actionlib_msgs.msg.GoalID)
00372 
00373             # for unknown reasons, we have to publish the message at least twice
00374             # to make it work
00375             for i in range(5):
00376                 move_base_pub.publish(rospy.Time.now(), '')
00377                 rospy.sleep(0.2)
00378 
00379     return 1
00380 
00381 
00382 
00383 def handle_dialog(req):
00384 
00385     global log
00386 
00387     human_waiting = Value('b', False)
00388     curr_goal = Array('c', "This is a very very very long string for nothing.")
00389 
00390     p1 = Process(target = gui_thread, args = (human_waiting, curr_goal))
00391     p2 = Process(target = platform_thread, args = (human_waiting, curr_goal))
00392 
00393     p1.start()
00394     p2.start()
00395 
00396     p1.join()
00397     p2.join()
00398 
00399     f = open('/home/bwi/shiqi/log.txt', 'w')
00400     f.write(log + '\n')
00401     f.close()
00402 
00403     return DialogResponse('/home/bwi/shiqi/log.txt')
00404  
00405 def main():
00406 
00407     rospy.init_node('dialog_server')    
00408     s = rospy.Service('dialog_service', Dialog, handle_dialog)
00409     rospy.spin()
00410 
00411 
00412 if __name__ == '__main__':
00413 
00414     main()
00415 


bwi_scavenger
Author(s): Shiqi Zhang
autogenerated on Thu Jun 6 2019 17:57:53