planner_krr2014.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 
00003 import time
00004 import rospy
00005 import shutil
00006 
00007 from bwi_planning.srv import CostLearnerInterface, CostLearnerInterfaceRequest
00008 from std_srvs.srv import Empty
00009 
00010 from .action_executor_krr2014 import ActionExecutorKRR2014
00011 from .clingo import ClingoWrapper
00012 from .atom_krr2014 import AtomKRR2014
00013 
00014 def get_adjacent_door(atoms):
00015     for atom in atoms:
00016         if atom.name == "beside" and not atom.negated:
00017             return str(atom.value)
00018     return None
00019 
00020 def get_location(atoms):
00021     for atom in atoms:
00022         if atom.name == "at":
00023             return str(atom.value)
00024     return None
00025 
00026 class PlannerKRR2014(object):
00027 
00028     def __init__(self):
00029         self.initialized = False
00030 
00031         self.dry_run = rospy.get_param("~dry_run", False)
00032         self.clingo_interface = ClingoWrapper(AtomKRR2014)
00033         initial_file = rospy.get_param("~initial_file", None)
00034         self.query_file = rospy.get_param("~query_file")
00035         self.domain_costs_file = rospy.get_param("~domain_costs_file", None)
00036         self.costs_file = rospy.get_param("~costs_file", None)
00037         self.enable_learning = rospy.get_param("~enable_learning", False)
00038 
00039         if self.dry_run and not initial_file:
00040             rospy.logfatal("Dry run requested, but no initial state provided." +
00041                            " Please set the ~initial_file param.")
00042             return
00043         self.initial_file = "/tmp/initial"
00044         if self.dry_run:
00045             rospy.loginfo("Supplied initial state written to: " + 
00046                           self.initial_file)
00047             shutil.copyfile(initial_file, self.initial_file)
00048 
00049         self.executor = ActionExecutorKRR2014(self.dry_run, self.initial_file)
00050 
00051         if self.enable_learning: 
00052             rospy.wait_for_service('cost_learner/increment_episode')
00053             rospy.wait_for_service('cost_learner/add_sample')
00054             self.finalize_episode = \
00055                     rospy.ServiceProxy('cost_learner/increment_episode', Empty)
00056             self.add_sample = \
00057                     rospy.ServiceProxy('cost_learner/add_sample', 
00058                                        CostLearnerInterface)
00059             self.planning_times_file = rospy.get_param("~planning_times_file",
00060                                                        None)
00061 
00062         self.initialized = True
00063 
00064     def _construct_initial_state(self, previous_state, observations):
00065         """
00066           This is a poor man's belief merge function between the previous_state
00067           and observations. This needs to be replaced with proper belief merge
00068           algorithms as it impossible to cover every possible situation here
00069           using if/else statements
00070         """
00071 
00072         new_state = []
00073         removed_atoms = []
00074         for atom in previous_state:
00075             atom.time = 0
00076             add_atom = True
00077             for observation in observations:
00078                 if observation.conflicts_with(atom):
00079                     add_atom = False
00080             if add_atom:
00081                 new_state.append(atom)
00082             else:
00083                 removed_atoms.append(atom)
00084 
00085         if len(removed_atoms) != 0:
00086             display_message = "  Incomaptible members in previous state: " 
00087             for atom in removed_atoms:
00088                 display_message += str(atom) + " "
00089             rospy.logwarn(display_message)
00090 
00091         for observation in observations:
00092             observation.time = 0
00093             new_state.append(observation)
00094 
00095         initial_file = open(self.initial_file,"w")
00096         display_message = "  Constructed state: "
00097         for atom in new_state:
00098             initial_file.write(str(atom) + ".\n")
00099             display_message += str(atom) + " "
00100         initial_file.close()
00101         rospy.loginfo(display_message)
00102         rospy.loginfo("Constructed initial state written to: " + 
00103                       self.initial_file)
00104 
00105     def _send_finish(self):
00106         if self.enable_learning:
00107             self.finalize_episode()
00108 
00109     def start(self):
00110         if not self.initialized:
00111             return
00112         self.executor.sense_initial_state()
00113         while True:
00114             if self.domain_costs_file != None:
00115                 rospy.loginfo("Planning with cost optimization!!")
00116                 start_time = time.time()
00117                 plan_available, optimization, plan, states = \
00118                         self.clingo_interface.get_plan_costs([self.initial_file,
00119                                                       self.query_file,
00120                                                       self.costs_file,
00121                                                       self.domain_costs_file])
00122                 duration = time.time() - start_time
00123                 if self.enable_learning and self.planning_times_file:
00124                     ptf = open(self.planning_times_file, "a")
00125                     ptf.write(str(duration) + "\n")
00126                     ptf.close()
00127             else:
00128                 plan_available, optimization, plan, states = \
00129                         self.clingo_interface.get_plan([self.initial_file,
00130                                                       self.query_file])
00131             if not plan_available:
00132                 rospy.logfatal("No plan found to complete task!")
00133                 break
00134             rospy.loginfo("Found plan (optimization = %i): %s"%(optimization,
00135                                                                 plan))
00136 
00137             need_replan = False
00138             for action in plan:
00139                 current_state = [state for state in states
00140                                  if state.time == action.time]
00141                 next_state = [state for state in states
00142                               if state.time == action.time+1]
00143                 start_time = rospy.get_time()
00144                 success, observations = \
00145                         self.executor.execute_action(action, next_state, 
00146                                                      action.time+1) 
00147                 duration = rospy.get_time() - start_time
00148                 if self.enable_learning and action.name == "approach":
00149                     if success:
00150                         # Check to see if we were beside some door in start
00151                         # state and the location
00152                         req = CostLearnerInterfaceRequest()
00153                         req.location = get_location(current_state)
00154                         req.door_from = get_adjacent_door(current_state)
00155                         if req.door_from:
00156                             req.door_to = str(action.value)
00157                             req.cost = duration
00158                             self.add_sample(req)
00159                     else:
00160                         rospy.loginfo("Executed unsuccessful approach action.")
00161 
00162                 for observation in observations:
00163                     if observation not in next_state:
00164                         rospy.logwarn("  Unexpected observation: " + 
00165                                       str(observation))
00166                         need_replan = True
00167                         break
00168                 if need_replan:
00169                     break
00170 
00171             if need_replan:
00172                 self._construct_initial_state(current_state, observations)
00173                 continue
00174             
00175             rospy.loginfo("Plan successful!")
00176             self._send_finish()
00177             break
00178 
00179 


bwi_planning
Author(s): Piyush Khandelwal , Fangkai Yang
autogenerated on Wed Aug 26 2015 10:54:52