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