solve-hanoi.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
5 
6 import roslib; roslib.load_manifest('pddl_planner')
7 import rospy
8 import os
9 
10 import actionlib
11 import pddl_msgs
12 from pddl_msgs.msg import *
13 
14 if __name__ == '__main__':
15  rospy.init_node('pddl_planner_client')
16  client = actionlib.SimpleActionClient('pddl_planner',
17  PDDLPlannerAction)
18  client.wait_for_server()
19  goal = PDDLPlannerGoal()
20  goal.domain.name = "manip"
21  goal.domain.requirements = ":typing"
22  goal.domain.types = "object"
23  goal.domain.predicates = ["(on ?obj0 ?obj1 - object)",
24  "(clear ?obj - object)",
25  "(ontable ?obj - object)",
26  "(holding ?obj - object)",
27  "(handempty)"]
28  pickup = PDDLAction()
29  pickup.name = "pickup"
30  pickup.parameters = "(?obj - object)"
31  pickup.precondition = "(and (ontable ?obj) (clear ?obj) (handempty))"
32  pickup.effect = """(and (not (ontable ?obj)) (not (clear ?obj))
33  (not (handempty)) (holding ?obj))"""
34  putdown = PDDLAction()
35  putdown.name = "putdown"
36  putdown.parameters = "(?obj - object)"
37  putdown.precondition = "(and (holding ?obj))"
38  putdown.effect = """(and
39  (not (holding ?obj))
40  (ontable ?obj)
41  (clear ?obj)
42  (handempty))"""
43  stack = PDDLAction()
44  stack.name = "stack"
45  stack.parameters = "(?obj0 ?obj1 - object)"
46  stack.precondition = """(and
47  (holding ?obj0)
48  (clear ?obj1))"""
49  stack.effect = """(and
50  (not (holding ?obj0))
51  (not (clear ?obj1))
52  (handempty)
53  (on ?obj0 ?obj1)
54  (clear ?obj0))"""
55  unstack = PDDLAction()
56  unstack.name = "unstack"
57  unstack.parameters = "(?obj0 ?obj1 - object)"
58  unstack.precondition = """(and
59  (handempty)
60  (on ?obj0 ?obj1)
61  (clear ?obj0))"""
62  unstack.effect = """(and
63  (not (handempty))
64  (not (on ?obj0 ?obj1))
65  (not (clear ?obj0))
66  (holding ?obj0)
67  (clear ?obj1))"""
68  goal.domain.actions = [pickup, unstack, stack, putdown]
69  goal.problem.name = "sample"
70  goal.problem.domain = "manip"
71  #goal.problem.objects = "a b c - obj"
72  goal.problem.objects = [PDDLObject(name="a", type="obj"),
73  PDDLObject(name="b", type="obj"),
74  PDDLObject(name="c", type="obj")]
75  goal.problem.initial = ["(on c a)",
76  "(ontable a)",
77  "(ontable b)",
78  "(clear b)",
79  "(clear c)",
80  "(handempty)"]
81  goal.problem.goal = "(and (on a b) (on b c))"
82  print(goal)
83  client.send_goal(goal)
84  client.wait_for_result()
85  print(client.get_result())
msg
actionlib::SimpleActionClient


pddl_planner
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Fri Dec 8 2023 03:35:32