pddl.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import os
00005 import re
00006 import signal
00007 import subprocess as sp
00008 import tempfile
00009 
00010 try:
00011     from pddl_msgs.msg import *
00012 except:
00013     import roslib; roslib.load_manifest('pddl_planner')
00014     from pddl_msgs.msg import *
00015 import actionlib
00016 
00017 
00018 class ActionPreemptedException(Exception):
00019     pass
00020 
00021 
00022 class ParseError(Exception):
00023     pass
00024 
00025 
00026 class PDDLPlannerActionServer(object):
00027     _result = PDDLPlannerResult()
00028     _feedback = PDDLPlannerFeedback()
00029     def __init__(self, name):
00030         self._action_name = name
00031         self._as = actionlib.SimpleActionServer(self._action_name,
00032                                                 PDDLPlannerAction,
00033                                                 self.execute_cb)
00034         # resolve rosparam
00035         self._planner_name = rospy.get_param('~pddl_planner', 'downward')
00036         search_option = rospy.get_param('~pddl_search_option', '')
00037         self._search_option = search_option.strip().split()
00038 
00039     def execute_cb(self, goal):
00040         try:
00041             problem = goal.problem
00042             domain = goal.domain
00043             rospy.loginfo("take a message")
00044             (problem_path, domain_path) = self.gen_tmp_pddl_file(problem, domain)
00045             rospy.loginfo("problem_path => %s" % problem_path)
00046             rospy.loginfo("domain_path => %s" % domain_path)
00047             result = self.call_pddl_planner(problem_path, domain_path)
00048 
00049             if self._planner_name == "lpg":
00050                 self._result.sequence = [PDDLStep(action = x.split(' ')[1].lstrip("\("),
00051                                                   args = re.search("\([^\)]+\)", x).group(0).lstrip("\(").rstrip("\)").split(' ')[1:],
00052                                                   start_time = re.search("[0-9]+.[0-9]+:" , x).group(0).rstrip(":"),
00053                                                   action_duration = re.search("\[D[^\)]+;", x).group(0).lstrip("[D:").rstrip(";")
00054                                                   )
00055                                          for x in result]
00056                 self._result.use_durative_action = True
00057             else:
00058                 self._result.sequence = [PDDLStep(action = x.split(' ')[0],
00059                                                   args = x.split(' ')[1:])
00060                                          for x in result]
00061             self._as.set_succeeded(self._result)
00062         except ActionPreemptedException:
00063             rospy.loginfo("action preempted")
00064             self._as.set_preempted()
00065         except ParseError:
00066             rospy.logerr("Failed to parse output")
00067             self._as.set_aborted()
00068         except RuntimeError as e:
00069             rospy.logerr("Planner exited with error: %s" % e)
00070             self._as.set_aborted()
00071         except Exception as e:
00072             rospy.logerr("Unhandled Error: %s" % e)
00073             self._as.set_aborted()
00074 
00075     def parse_pddl_result(self, output):
00076         rospy.loginfo(output)
00077         # dirty implementation
00078         step_before_after = output.split("step")
00079         if len(step_before_after) == 2:
00080             results = [re.sub("\s*$", "", re.sub(r'^\s*\d+:\s*', "" , x))
00081                        for x in step_before_after[1].split("time spent")[0].split("\n")]
00082             rospy.loginfo("result => %s" % results)
00083             return filter(lambda x: x != "", results)
00084         else:
00085             raise ParseError()
00086     def parse_pddl_result_ffha(self, output):
00087         rospy.loginfo(output)
00088         # dirty implementation
00089         step_before_after = output.split("step")
00090         if len(step_before_after) == 2:
00091             results = [y.group(0)
00092                        for y in [re.search("\([^\)]+\)", x)
00093                                  for x in step_before_after[1].split("Total cost")[0].split("\n")[1:]]
00094                        if y != None]
00095             results = filter(lambda a: a.find("(REACH-GOAL)") < 0, results)
00096             rospy.loginfo("result => %s" % results)
00097             return results
00098         else:
00099             raise ParseError()
00100 
00101     def parse_pddl_result_lpg(self, output):
00102         rospy.loginfo(output)
00103         #dirty implementation
00104         duration_before_after = output.split("action Duration")
00105         if len(duration_before_after) == 2:
00106             results = [y.group(0)
00107                        for y in [re.search("[0-9][^\]]+\]", x)
00108                                  for x in duration_before_after[1].split("Solution number")[0].split("\n")[1:]]
00109                        if y != None]
00110             rospy.loginfo("result => %s" % results)
00111             return results
00112         else:
00113             raise ParseError()
00114 
00115     def parse_pddl_result_downward(self, path_name):
00116         plan_path = path_name
00117         i = 1
00118         while os.path.exists(path_name + "." + str(i)):
00119             plan_path = path_name + "." + str(i)
00120             i += 1
00121         rospy.loginfo("plan_path => %s" % plan_path)
00122 
00123         with open(plan_path) as f:
00124             plan = f.read().split("\n")
00125 
00126         plan.remove("")
00127         results = [re.sub(" \)$", ")", x)
00128                    for x in plan]
00129         rospy.loginfo(results)
00130 
00131         return results
00132 
00133     def exec_process(self, command):
00134         try:
00135             proc = sp.Popen(command, stdout=sp.PIPE, stderr=sp.PIPE)
00136             r = rospy.Rate(10.0)
00137             while True:
00138                 if rospy.is_shutdown():
00139                     return None
00140                 if self._as.is_preempt_requested():
00141                     raise ActionPreemptedException()
00142                 if proc.poll() is not None:
00143                     break
00144                 r.sleep()
00145             output, error = proc.communicate()
00146             if proc.poll() != 0:
00147                 # process exited abnormally
00148                 raise RuntimeError(error)
00149             return output
00150         finally:
00151             self.kill_process(proc)
00152 
00153     def kill_process(self, proc):
00154         if proc is None or proc.poll() is not None:
00155             return
00156         try:
00157             # 1. SIGINT
00158             proc.send_signal(signal.SIGINT)
00159             rospy.sleep(10.0)
00160 
00161             if proc.poll() is not None:
00162                 return
00163 
00164             # 2. Escalated to SIGTERM
00165             proc.send_signal(signal.SIGTERM)
00166             rospy.sleep(3.0)
00167 
00168             if proc.poll() is not None:
00169                 return
00170 
00171             # 3. Escalated to SIGKILL
00172             proc.kill()
00173             proc.wait()
00174         except Exception as e:
00175             rospy.logerr("Failed to kill process: %s" % e)
00176 
00177 
00178     def call_pddl_planner(self, problem, domain):
00179 
00180         if  self._planner_name == "ff":
00181             # -f problem -o domain
00182             output = self.exec_process(["rosrun", "ff", "ff", "-f", problem, "-o", domain])
00183             return self.parse_pddl_result(output)
00184 
00185         # ffha
00186         elif self._planner_name == "ffha":
00187             output = self.exec_process(["rosrun", "ffha", "ffha"] + self._search_option + ["-f", problem, "-o", domain])
00188             if re.search("final domain representation is:", output):
00189                 tmp = output.split("metric:")
00190                 if len(tmp) > 1:
00191                     output = tmp[1];
00192                 self._result.data = tmp;
00193             return self.parse_pddl_result_ffha(output)
00194         # downward
00195         elif self._planner_name == "downward":
00196             (fd, path_name) = tempfile.mkstemp(text=True, prefix='plan_')
00197             output = self.exec_process(["rosrun", "downward", "plan", domain, problem] + self._search_option + ["--plan-file", path_name])
00198             rospy.loginfo(output)
00199             self._result.data = output
00200             return self.parse_pddl_result_downward(path_name)
00201         # lpg
00202         elif self._planner_name == "lpg":
00203             output = self.exec_process(["rosrun", "lpg_planner", "lpg-1.2"] + self._search_option + ["-f", problem, "-o", domain])
00204             return self.parse_pddl_result_lpg(output)
00205 
00206         else:
00207             rospy.logfatal("set invalid planner: %s !" % self._planner_name)
00208             return
00209 
00210     def gen_tmp_pddl_file(self, problem, domain):
00211         search_durative = re.search("durative", domain.requirements)
00212         rospy.loginfo ("gen_tmp_pddl_file: requirements:%s" % domain.requirements)
00213         if search_durative == None:
00214             problem_file = self.gen_tmp_problem_pddl_file(problem)
00215             domain_file = self.gen_tmp_domain_pddl_file(domain)
00216             return (problem_file, domain_file)
00217         else:
00218             problem_file = self.gen_tmp_problem_pddl_file(problem)
00219             domain_file = self.gen_tmp_durative_domain_pddl_file(domain)
00220             return (problem_file, domain_file)
00221     def gen_problem_objects_strings(self, objects):
00222         # objects = list of PDDLObject
00223         # PDDLObject has name and type
00224         # collect PDDLObjects which has the same type
00225         grouped_objects = {}
00226         # grouped_objects := (type_and_objects ...)
00227         # type_and_objects := (type_name object_a object_b ...)
00228         # destructively change grouped_objects
00229         for o in objects:
00230             object_name = o.name
00231             # find same object_type in grouped_objects
00232             if grouped_objects.has_key(o.type):
00233                 grouped_objects[o.type].append(o.name)
00234             else:
00235                 grouped_objects[o.type] = [o.name]
00236         return [" ".join(grouped_objects[t]) + " - " + t
00237                 for t in grouped_objects.keys()]
00238     
00239     def gen_tmp_problem_pddl_file(self, problem):
00240         (fd, path_name) = tempfile.mkstemp(text=True, prefix='problem_')
00241         path = os.fdopen(fd, 'w')
00242         path.write("""(define (problem %s)
00243 (:domain %s)
00244 (:objects %s)
00245 (:init %s)
00246 (:goal %s)
00247 """ % (problem.name, problem.domain,
00248        "\n".join(self.gen_problem_objects_strings(problem.objects)),
00249        ' '.join(problem.initial), problem.goal))
00250         if problem.metric:
00251             path.write("""(:metric %s)""" % problem.metric)
00252         path.write(""")""")
00253         return path_name
00254 
00255     def gen_tmp_domain_pddl_file(self, domain):
00256         (fd, path_name) = tempfile.mkstemp(text=True, prefix='domain_')
00257         path = os.fdopen(fd, 'w')
00258         path.write("(define (domain %s)\n" % domain.name)
00259         path.write("(:requirements %s)\n" % domain.requirements)
00260         path.write("(:types \n")
00261         for i in domain.types:
00262             path.write(i + " ")
00263         path.write(")\n")
00264         if len(domain.constants) > 0:
00265             path.write("(:constants \n")
00266             for i in domain.constants:
00267                 path.write(i + " ")
00268             path.write(")\n")
00269         path.write("(:predicates\n")
00270         for i in domain.predicates:
00271             path.write(i + " ")
00272         path.write(")\n")
00273         if domain.functions:
00274             path.write("(:functions\n")
00275             for i in domain.functions:
00276                 path.write(i + " ")
00277             path.write(")\n")
00278         for action in domain.actions:
00279             path.write("(:action %s\n" % action.name)
00280             path.write(":parameters %s\n" % action.parameters)
00281             path.write(":precondition %s\n" % action.precondition)
00282             path.write(":effect %s\n" % action.effect)
00283             path.write(")\n")               # (:action
00284         path.write(")\n")               # (define
00285         return path_name
00286     
00287     def gen_tmp_durative_domain_pddl_file(self, domain):
00288         rospy.loginfo("domain.actions:%s" % domain.actions)
00289         (fd, path_name) = tempfile.mkstemp(text=True, prefix='domain_')
00290         path = os.fdopen(fd, 'w')
00291         path.write("(define (domain %s)\n" % domain.name)
00292         path.write("(:requirements %s)\n" % domain.requirements)
00293         path.write("(:types \n")
00294         for i in domain.types:
00295             path.write(i + " ")
00296         path.write(")\n")
00297         if len(domain.constants) > 0:
00298             path.write("(:constants \n")
00299             for i in domain.constants:
00300                 path.write(i + " ")
00301             path.write(")\n")
00302         path.write("(:predicates\n")
00303         for i in domain.predicates:
00304             path.write(i + " ")
00305         path.write(")\n")
00306         if domain.functions:
00307             path.write("(:functions\n")
00308             for i in domain.functions:
00309                 path.write(i + " ")
00310             path.write(")\n")
00311         for action in domain.actions:
00312             path.write("(:durative-action %s\n" % action.name)
00313             path.write(":parameters %s\n" % action.parameters)
00314             path.write(":duration %s\n" % action.action_duration)
00315             path.write(":condition %s\n" % action.precondition)
00316             path.write(":effect %s\n" % action.effect)
00317             path.write(")\n")               # (:action
00318         path.write(")\n")               # (define
00319         return path_name
00320     
00321 
00322 if __name__ == '__main__':
00323     rospy.init_node('pddl_planner')
00324     PDDLPlannerActionServer(rospy.get_name())
00325     rospy.spin()


pddl_planner
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Sat Jun 8 2019 19:23:56