solve-hanoi.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 ## this is the ros-client version of sample hanoi example of pddl_planner package
00004 ## demos/sample-pddl/sample-domain.pddl, demos/sample-pddl/sample-problem.pddl
00005 
00006 import roslib; roslib.load_manifest('pddl_planner')
00007 import rospy
00008 import os
00009 
00010 import actionlib
00011 import pddl_msgs
00012 from pddl_msgs.msg import *
00013 
00014 if __name__ == '__main__':
00015     rospy.init_node('pddl_planner_client')
00016     client = actionlib.SimpleActionClient('pddl_planner',
00017                                           PDDLPlannerAction)
00018     client.wait_for_server()
00019     goal = PDDLPlannerGoal()
00020     goal.domain.name = "manip"
00021     goal.domain.requirements = ":typing"
00022     goal.domain.types = "object"
00023     goal.domain.predicates = ["(on ?obj0 ?obj1 - object)",
00024                                    "(clear ?obj - object)",
00025                                    "(ontable ?obj - object)",
00026                                    "(holding ?obj - object)",
00027                                    "(handempty)"]
00028     pickup = PDDLAction()
00029     pickup.name = "pickup"
00030     pickup.parameters = "(?obj - object)"
00031     pickup.precondition = "(and (ontable ?obj) (clear ?obj) (handempty))"
00032     pickup.effect = """(and (not (ontable ?obj)) (not (clear ?obj))
00033     (not (handempty)) (holding ?obj))"""
00034     putdown = PDDLAction()
00035     putdown.name = "putdown"
00036     putdown.parameters = "(?obj - object)"
00037     putdown.precondition = "(and (holding ?obj))"
00038     putdown.effect = """(and
00039     (not (holding ?obj))
00040     (ontable ?obj)
00041     (clear ?obj)
00042     (handempty))"""
00043     stack = PDDLAction()
00044     stack.name = "stack"
00045     stack.parameters = "(?obj0 ?obj1 - object)"
00046     stack.precondition = """(and 
00047     (holding ?obj0)
00048     (clear ?obj1))"""
00049     stack.effect = """(and
00050     (not (holding ?obj0))
00051     (not (clear ?obj1))
00052     (handempty)
00053     (on ?obj0 ?obj1)
00054     (clear ?obj0))"""
00055     unstack = PDDLAction()
00056     unstack.name = "unstack"
00057     unstack.parameters = "(?obj0 ?obj1 - object)"
00058     unstack.precondition = """(and 
00059                         (handempty)
00060                         (on ?obj0 ?obj1)
00061                         (clear ?obj0))"""
00062     unstack.effect = """(and
00063                  (not (handempty))
00064                  (not (on ?obj0 ?obj1))
00065                  (not (clear ?obj0))
00066                  (holding ?obj0)
00067                  (clear ?obj1))"""
00068     goal.domain.actions = [pickup, unstack, stack, putdown]
00069     goal.problem.name = "sample"
00070     goal.problem.domain = "manip"
00071     #goal.problem.objects = "a b c - obj"
00072     goal.problem.objects = [PDDLObject(name="a", type="obj"),
00073                             PDDLObject(name="b", type="obj"),
00074                             PDDLObject(name="c", type="obj")]
00075     goal.problem.initial = ["(on c a)", 
00076                             "(ontable a)",
00077                             "(ontable b)",
00078                             "(clear b)",
00079                             "(clear c)",
00080                             "(handempty)"]
00081     goal.problem.goal = "(and (on a b) (on b c))"
00082     print goal
00083     client.send_goal(goal)
00084     client.wait_for_result()
00085     print client.get_result() 


pddl_planner
Author(s): Ryohei Ueda (ueda@jsk.t.u-tokyo.ac.jp)
autogenerated on Sat Jun 8 2019 19:23:56