8 import subprocess
as sp
28 fl = fcntl.fcntl(fd, fcntl.F_GETFL)
29 fcntl.fcntl(fd, fcntl.F_SETFL, fl | os.O_NONBLOCK)
41 _result = PDDLPlannerResult()
48 search_option = rospy.get_param(
'~pddl_search_option',
'')
55 problem = goal.problem
57 max_planning_time = goal.max_planning_time.to_sec()
58 rospy.loginfo(
"take a message")
60 rospy.loginfo(
"problem_path => %s" % problem_path)
61 rospy.loginfo(
"domain_path => %s" % domain_path)
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(
";")
71 self.
_result.use_durative_action =
True 73 self.
_result.sequence = [PDDLStep(action = x.split(
' ')[0],
74 args = x.split(
' ')[1:])
77 rospy.loginfo(
"action finished with success")
78 except ActionPreemptedException:
79 rospy.loginfo(
"action preempted")
80 self.
_as.set_preempted()
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()
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)
104 rospy.loginfo(output)
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:]]
112 results = filter(
lambda a: a.find(
"(REACH-GOAL)") < 0, results)
113 rospy.loginfo(
"result => %s" % results)
119 rospy.loginfo(output)
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:]]
127 rospy.loginfo(
"result => %s" % results)
133 plan_path = path_name
135 while os.path.exists(path_name +
"." + str(i)):
136 plan_path = path_name +
"." + str(i)
138 rospy.loginfo(
"plan_path => %s" % plan_path)
140 with open(plan_path)
as f:
141 plan = f.read().split(
"\n")
144 results = [re.sub(
" \)$",
")", x)
146 rospy.loginfo(results)
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)
156 output, error = str(), str()
159 if rospy.is_shutdown():
161 if self.
_as.is_preempt_requested():
163 if proc.poll()
is not None:
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')
177 data = proc.communicate()
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')
187 if proc.returncode
not in [0, 124]:
191 msg =
"Output:\n" + output +
"\n" 192 msg +=
"Error:\n" + error +
"\n" 193 msg +=
"Exit code: {}\n".format(proc.poll())
194 raise RuntimeError(msg)
200 if proc
is None or proc.poll()
is not None:
204 proc.send_signal(signal.SIGINT)
207 if proc.poll()
is not None:
211 proc.send_signal(signal.SIGTERM)
214 if proc.poll()
is not None:
220 except Exception
as e:
221 rospy.logerr(
"Failed to kill process: %s" % e)
228 output = self.
exec_process([
"rosrun",
"ff",
"ff",
"-f", problem,
"-o", domain],
236 if re.search(
"final domain representation is:", output):
237 tmp = output.split(
"metric:")
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],
247 rospy.loginfo(output)
257 rospy.logfatal(
"set invalid planner: %s !" % self.
_planner_name)
261 search_durative = re.search(
"durative", domain.requirements)
262 rospy.loginfo (
"gen_tmp_pddl_file: requirements:%s" % domain.requirements)
263 if search_durative ==
None:
266 return (problem_file, domain_file)
270 return (problem_file, domain_file)
283 if o.type
in grouped_objects:
284 grouped_objects[o.type].append(o.name)
286 grouped_objects[o.type] = [o.name]
287 return [
" ".join(grouped_objects[t]) +
" - " + t
288 for t
in grouped_objects.keys()]
291 (fd, path_name) = tempfile.mkstemp(text=
True, prefix=
'problem_')
292 path = os.fdopen(fd,
'w')
293 path.write(
"""(define (problem %s) 298 """ % (problem.name, problem.domain,
300 ' '.join(problem.initial), problem.goal))
302 path.write(
"""(:metric %s)""" % problem.metric)
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:
315 if len(domain.constants) > 0:
316 path.write(
"(:constants \n")
317 for i
in domain.constants:
320 path.write(
"(:predicates\n")
321 for i
in domain.predicates:
325 path.write(
"(:functions\n")
326 for i
in domain.functions:
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)
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:
348 if len(domain.constants) > 0:
349 path.write(
"(:constants \n")
350 for i
in domain.constants:
353 path.write(
"(:predicates\n")
354 for i
in domain.predicates:
358 path.write(
"(:functions\n")
359 for i
in domain.functions:
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)
373 if __name__ ==
'__main__':
374 rospy.init_node(
'pddl_planner')
def gen_tmp_domain_pddl_file(self, domain)
def call_pddl_planner(self, problem, domain, max_planning_time)
def parse_pddl_result(self, output)
def gen_tmp_pddl_file(self, problem, domain)
def exec_process(self, command, max_planning_time)
def gen_tmp_durative_domain_pddl_file(self, domain)
def parse_pddl_result_downward(self, path_name)
def execute_cb(self, goal)
def gen_tmp_problem_pddl_file(self, problem)
def kill_process(self, proc)
def parse_pddl_result_lpg(self, output)
def parse_pddl_result_ffha(self, output)
def read_out(out, nonblock=True)
def gen_problem_objects_strings(self, objects)