pddl.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import fcntl
4 import rospy
5 import os
6 import re
7 import signal
8 import subprocess as sp
9 import sys
10 import tempfile
11 import traceback
12 
13 from pddl_msgs.msg import *
14 import actionlib
15 
16 
17 class ActionPreemptedException(Exception):
18  pass
19 
20 
21 class ParseError(Exception):
22  pass
23 
24 
25 def read_out(out, nonblock=True):
26  if nonblock:
27  fd = out.fileno()
28  fl = fcntl.fcntl(fd, fcntl.F_GETFL)
29  fcntl.fcntl(fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
30  try:
31  ret = out.read()
32  if ret == None:
33  return str()
34  else:
35  return ret
36  except:
37  return str()
38 
39 
41  _result = PDDLPlannerResult()
42  def __init__(self, name):
43  self._action_name = name
45  self._action_name, PDDLPlannerAction, self.execute_cb, auto_start=False)
46  # resolve rosparam
47  self._planner_name = rospy.get_param('~pddl_planner', 'downward')
48  search_option = rospy.get_param('~pddl_search_option', '')
49  self._search_option = search_option.strip().split()
50 
51  self._as.start()
52 
53  def execute_cb(self, goal):
54  try:
55  problem = goal.problem
56  domain = goal.domain
57  max_planning_time = goal.max_planning_time.to_sec()
58  rospy.loginfo("take a message")
59  (problem_path, domain_path) = self.gen_tmp_pddl_file(problem, domain)
60  rospy.loginfo("problem_path => %s" % problem_path)
61  rospy.loginfo("domain_path => %s" % domain_path)
62  result = self.call_pddl_planner(problem_path, domain_path, max_planning_time)
63 
64  if self._planner_name == "lpg":
65  self._result.sequence = [PDDLStep(action = x.split(' ')[1].lstrip("\("),
66  args = re.search("\([^\)]+\)", x).group(0).lstrip("\(").rstrip("\)").split(' ')[1:],
67  start_time = re.search("[0-9]+.[0-9]+:" , x).group(0).rstrip(":"),
68  action_duration = re.search("\[D[^\)]+;", x).group(0).lstrip("[D:").rstrip(";")
69  )
70  for x in result]
71  self._result.use_durative_action = True
72  else:
73  self._result.sequence = [PDDLStep(action = x.split(' ')[0],
74  args = x.split(' ')[1:])
75  for x in result]
76  self._as.set_succeeded(self._result)
77  rospy.loginfo("action finished with success")
78  except ActionPreemptedException:
79  rospy.loginfo("action preempted")
80  self._as.set_preempted()
81  except ParseError:
82  rospy.logerr("Failed to parse output")
83  self._as.set_aborted()
84  except RuntimeError as e:
85  rospy.logerr("Planner exited with error: %s" % e)
86  self._as.set_aborted()
87  except Exception as e:
88  rospy.logerr("Unhandled Error: %s" % e)
89  rospy.logerr(traceback.format_exc())
90  self._as.set_aborted()
91 
92  def parse_pddl_result(self, output):
93  rospy.loginfo(output)
94  # dirty implementation
95  step_before_after = output.split("step")
96  if len(step_before_after) == 2:
97  results = [re.sub("\s*$", "", re.sub(r'^\s*\d+:\s*', "" , x))
98  for x in step_before_after[1].split("time spent")[0].split("\n")]
99  rospy.loginfo("result => %s" % results)
100  return filter(lambda x: x != "", results)
101  else:
102  raise ParseError()
103  def parse_pddl_result_ffha(self, output):
104  rospy.loginfo(output)
105  # dirty implementation
106  step_before_after = output.split("step")
107  if len(step_before_after) == 2:
108  results = [y.group(0)
109  for y in [re.search("\([^\)]+\)", x)
110  for x in step_before_after[1].split("Total cost")[0].split("\n")[1:]]
111  if y != None]
112  results = filter(lambda a: a.find("(REACH-GOAL)") < 0, results)
113  rospy.loginfo("result => %s" % results)
114  return results
115  else:
116  raise ParseError()
117 
118  def parse_pddl_result_lpg(self, output):
119  rospy.loginfo(output)
120  #dirty implementation
121  duration_before_after = output.split("action Duration")
122  if len(duration_before_after) == 2:
123  results = [y.group(0)
124  for y in [re.search("[0-9][^\]]+\]", x)
125  for x in duration_before_after[1].split("Solution number")[0].split("\n")[1:]]
126  if y != None]
127  rospy.loginfo("result => %s" % results)
128  return results
129  else:
130  raise ParseError()
131 
132  def parse_pddl_result_downward(self, path_name):
133  plan_path = path_name
134  i = 1
135  while os.path.exists(path_name + "." + str(i)):
136  plan_path = path_name + "." + str(i)
137  i += 1
138  rospy.loginfo("plan_path => %s" % plan_path)
139 
140  with open(plan_path) as f:
141  plan = f.read().split("\n")
142 
143  plan.remove("")
144  results = [re.sub(" \)$", ")", x)
145  for x in plan]
146  rospy.loginfo(results)
147 
148  return results
149 
150  def exec_process(self, command, max_planning_time):
151  if max_planning_time > 0.0:
152  command = ["timeout", str(max_planning_time)] + command
153  rospy.loginfo("Command: %s" % " ".join(command))
154  proc = sp.Popen(" ".join(command), stdout=sp.PIPE, stderr=sp.PIPE, shell=True)
155  try:
156  output, error = str(), str()
157  r = rospy.Rate(10.0)
158  while True:
159  if rospy.is_shutdown():
160  return None
161  if self._as.is_preempt_requested():
163  if proc.poll() is not None:
164  break
165  # non-blocking read to avoid dead-lock
166  data_out = read_out(proc.stdout)
167  data_err = read_out(proc.stderr)
168  if type(data_out) == bytes:
169  data_out = data_out.decode('utf-8')
170  if type(data_err) == bytes:
171  data_err = data_err.decode('utf-8')
172  output += data_out
173  error += data_err
174  r.sleep()
175 
176  # flush output
177  data = proc.communicate()
178  data_out = data[0]
179  data_err = data[1]
180  if type(data_out) == bytes:
181  data_out = data_out.decode('utf-8')
182  if type(data_err) == bytes:
183  data_err = data_err.decode('utf-8')
184  output += data_out
185  error += data_err
186 
187  if proc.returncode not in [0, 124]:
188  # 0: normal exit
189  # 124: exited with timeout command
190  # others: process exited abnormally
191  msg = "Output:\n" + output + "\n"
192  msg += "Error:\n" + error + "\n"
193  msg += "Exit code: {}\n".format(proc.poll())
194  raise RuntimeError(msg)
195  return output
196  finally:
197  self.kill_process(proc)
198 
199  def kill_process(self, proc):
200  if proc is None or proc.poll() is not None:
201  return
202  try:
203  # 1. SIGINT
204  proc.send_signal(signal.SIGINT)
205  rospy.sleep(10.0)
206 
207  if proc.poll() is not None:
208  return
209 
210  # 2. Escalated to SIGTERM
211  proc.send_signal(signal.SIGTERM)
212  rospy.sleep(3.0)
213 
214  if proc.poll() is not None:
215  return
216 
217  # 3. Escalated to SIGKILL
218  proc.kill()
219  proc.wait()
220  except Exception as e:
221  rospy.logerr("Failed to kill process: %s" % e)
222 
223 
224  def call_pddl_planner(self, problem, domain, max_planning_time):
225 
226  if self._planner_name == "ff":
227  # -f problem -o domain
228  output = self.exec_process(["rosrun", "ff", "ff", "-f", problem, "-o", domain],
229  max_planning_time)
230  return self.parse_pddl_result(output)
231 
232  # ffha
233  elif self._planner_name == "ffha":
234  output = self.exec_process(["rosrun", "ffha", "ffha"] + self._search_option + ["-f", problem, "-o", domain],
235  max_planning_time)
236  if re.search("final domain representation is:", output):
237  tmp = output.split("metric:")
238  if len(tmp) > 1:
239  output = tmp[1];
240  self._result.data = tmp;
241  return self.parse_pddl_result_ffha(output)
242  # downward
243  elif self._planner_name == "downward":
244  (fd, path_name) = tempfile.mkstemp(text=True, prefix='plan_')
245  output = self.exec_process(["rosrun", "downward", "plan", domain, problem] + self._search_option + ["--plan-file", path_name],
246  max_planning_time)
247  rospy.loginfo(output)
248  self._result.data = output
249  return self.parse_pddl_result_downward(path_name)
250  # lpg
251  elif self._planner_name == "lpg":
252  output = self.exec_process(["rosrun", "lpg_planner", "lpg-1.2"] + self._search_option + ["-f", problem, "-o", domain],
253  max_planning_time)
254  return self.parse_pddl_result_lpg(output)
255 
256  else:
257  rospy.logfatal("set invalid planner: %s !" % self._planner_name)
258  return
259 
260  def gen_tmp_pddl_file(self, problem, domain):
261  search_durative = re.search("durative", domain.requirements)
262  rospy.loginfo ("gen_tmp_pddl_file: requirements:%s" % domain.requirements)
263  if search_durative == None:
264  problem_file = self.gen_tmp_problem_pddl_file(problem)
265  domain_file = self.gen_tmp_domain_pddl_file(domain)
266  return (problem_file, domain_file)
267  else:
268  problem_file = self.gen_tmp_problem_pddl_file(problem)
269  domain_file = self.gen_tmp_durative_domain_pddl_file(domain)
270  return (problem_file, domain_file)
271 
272  def gen_problem_objects_strings(self, objects):
273  # objects = list of PDDLObject
274  # PDDLObject has name and type
275  # collect PDDLObjects which has the same type
276  grouped_objects = {}
277  # grouped_objects := (type_and_objects ...)
278  # type_and_objects := (type_name object_a object_b ...)
279  # destructively change grouped_objects
280  for o in objects:
281  object_name = o.name
282  # find same object_type in grouped_objects
283  if o.type in grouped_objects:
284  grouped_objects[o.type].append(o.name)
285  else:
286  grouped_objects[o.type] = [o.name]
287  return [" ".join(grouped_objects[t]) + " - " + t
288  for t in grouped_objects.keys()]
289 
290  def gen_tmp_problem_pddl_file(self, problem):
291  (fd, path_name) = tempfile.mkstemp(text=True, prefix='problem_')
292  path = os.fdopen(fd, 'w')
293  path.write("""(define (problem %s)
294 (:domain %s)
295 (:objects %s)
296 (:init %s)
297 (:goal %s)
298 """ % (problem.name, problem.domain,
299  "\n".join(self.gen_problem_objects_strings(problem.objects)),
300  ' '.join(problem.initial), problem.goal))
301  if problem.metric:
302  path.write("""(:metric %s)""" % problem.metric)
303  path.write(""")""")
304  return path_name
305 
306  def gen_tmp_domain_pddl_file(self, domain):
307  (fd, path_name) = tempfile.mkstemp(text=True, prefix='domain_')
308  path = os.fdopen(fd, 'w')
309  path.write("(define (domain %s)\n" % domain.name)
310  path.write("(:requirements %s)\n" % domain.requirements)
311  path.write("(:types \n")
312  for i in domain.types:
313  path.write(i + " ")
314  path.write(")\n")
315  if len(domain.constants) > 0:
316  path.write("(:constants \n")
317  for i in domain.constants:
318  path.write(i + " ")
319  path.write(")\n")
320  path.write("(:predicates\n")
321  for i in domain.predicates:
322  path.write(i + " ")
323  path.write(")\n")
324  if domain.functions:
325  path.write("(:functions\n")
326  for i in domain.functions:
327  path.write(i + " ")
328  path.write(")\n")
329  for action in domain.actions:
330  path.write("(:action %s\n" % action.name)
331  path.write(":parameters %s\n" % action.parameters)
332  path.write(":precondition %s\n" % action.precondition)
333  path.write(":effect %s\n" % action.effect)
334  path.write(")\n") # (:action
335  path.write(")\n") # (define
336  return path_name
337 
339  rospy.loginfo("domain.actions:%s" % domain.actions)
340  (fd, path_name) = tempfile.mkstemp(text=True, prefix='domain_')
341  path = os.fdopen(fd, 'w')
342  path.write("(define (domain %s)\n" % domain.name)
343  path.write("(:requirements %s)\n" % domain.requirements)
344  path.write("(:types \n")
345  for i in domain.types:
346  path.write(i + " ")
347  path.write(")\n")
348  if len(domain.constants) > 0:
349  path.write("(:constants \n")
350  for i in domain.constants:
351  path.write(i + " ")
352  path.write(")\n")
353  path.write("(:predicates\n")
354  for i in domain.predicates:
355  path.write(i + " ")
356  path.write(")\n")
357  if domain.functions:
358  path.write("(:functions\n")
359  for i in domain.functions:
360  path.write(i + " ")
361  path.write(")\n")
362  for action in domain.actions:
363  path.write("(:durative-action %s\n" % action.name)
364  path.write(":parameters %s\n" % action.parameters)
365  path.write(":duration %s\n" % action.action_duration)
366  path.write(":condition %s\n" % action.precondition)
367  path.write(":effect %s\n" % action.effect)
368  path.write(")\n") # (:action
369  path.write(")\n") # (define
370  return path_name
371 
372 
373 if __name__ == '__main__':
374  rospy.init_node('pddl_planner')
375  PDDLPlannerActionServer(rospy.get_name())
376  rospy.spin()
def gen_tmp_domain_pddl_file(self, domain)
Definition: pddl.py:306
def __init__(self, name)
Definition: pddl.py:42
def call_pddl_planner(self, problem, domain, max_planning_time)
Definition: pddl.py:224
def parse_pddl_result(self, output)
Definition: pddl.py:92
def gen_tmp_pddl_file(self, problem, domain)
Definition: pddl.py:260
def exec_process(self, command, max_planning_time)
Definition: pddl.py:150
def gen_tmp_durative_domain_pddl_file(self, domain)
Definition: pddl.py:338
def parse_pddl_result_downward(self, path_name)
Definition: pddl.py:132
def execute_cb(self, goal)
Definition: pddl.py:53
def gen_tmp_problem_pddl_file(self, problem)
Definition: pddl.py:290
def kill_process(self, proc)
Definition: pddl.py:199
def parse_pddl_result_lpg(self, output)
Definition: pddl.py:118
def parse_pddl_result_ffha(self, output)
Definition: pddl.py:103
def read_out(out, nonblock=True)
Definition: pddl.py:25
def gen_problem_objects_strings(self, objects)
Definition: pddl.py:272


pddl_planner
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Fri Oct 21 2022 02:26:17