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