6 import roslib; roslib.load_manifest(
'pddl_planner')
14 if __name__ ==
'__main__':
15 rospy.init_node(
'pddl_planner_client')
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)",
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
45 stack.parameters =
"(?obj0 ?obj1 - object)"
46 stack.precondition =
"""(and
49 stack.effect =
"""(and
55 unstack = PDDLAction()
56 unstack.name =
"unstack"
57 unstack.parameters =
"(?obj0 ?obj1 - object)"
58 unstack.precondition =
"""(and
62 unstack.effect =
"""(and
64 (not (on ?obj0 ?obj1))
68 goal.domain.actions = [pickup, unstack, stack, putdown]
69 goal.problem.name =
"sample"
70 goal.problem.domain =
"manip"
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)",
81 goal.problem.goal =
"(and (on a b) (on b c))"
83 client.send_goal(goal)
84 client.wait_for_result()
85 print(client.get_result())