TestMemory.py
Go to the documentation of this file.
00001 # Copyright (c) 2013, Felix Kolbe
00002 # All rights reserved. BSD License
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 # * Redistributions of source code must retain the above copyright
00009 #   notice, this list of conditions and the following disclaimer.
00010 #
00011 # * Redistributions in binary form must reproduce the above copyright
00012 #   notice, this list of conditions and the following disclaimer in the
00013 #   documentation and/or other materials provided with the distribution.
00014 #
00015 # * Neither the name of the {organization} nor the names of its
00016 #   contributors may be used to endorse or promote products derived
00017 #   from this software without specific prior written permission.
00018 #
00019 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00020 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00021 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
00022 # A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
00023 # HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
00024 # SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00025 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00026 # DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
00027 # THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00028 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00029 # OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00030 
00031 
00032 import unittest
00033 
00034 from rgoap.common import *
00035 from rgoap.memory import *
00036 from rgoap.planning import Node
00037 from rgoap.runner import Runner
00038 
00039 
00040 #@unittest.skip
00041 class TestSimple(unittest.TestCase):
00042 
00043     def setUp(self):
00044         self.runner = Runner()
00045 
00046         self.memory = self.runner.memory
00047         self.worldstate = self.runner.worldstate
00048 
00049         self.memory.set_value('memory.counter', 0)
00050 
00051         print self.memory
00052 
00053         Condition._conditions_dict.clear() # start every test without previous conditions
00054 
00055         Condition.add(MemoryCondition(self.memory, 'memory.counter'))
00056 
00057         print Condition.print_dict()
00058 
00059         self.actions = self.runner.actions
00060         self.actions.add(MemoryChangeVarAction(self.memory, 'memory.counter', 2, 3))
00061         self.actions.add(MemoryChangeVarAction(self.memory, 'memory.counter', 0, 1))
00062         self.actions.add(MemoryChangeVarAction(self.memory, 'memory.counter', 1, 2))
00063         self.actions.add(MemoryChangeVarAction(self.memory, 'memory.counter', -2, 3))
00064 
00065         print self.actions
00066 
00067         self.goal = Goal([Precondition(Condition.get('memory.counter'), 3)])
00068 
00069         self.goal_inaccessible = Goal([Precondition(Condition.get('memory.counter'), 4)])
00070 
00071         print self.worldstate
00072 
00073         print self.runner
00074 
00075     def testGoals(self):
00076         print '==', self.testGoals.__name__
00077         Condition.initialize_worldstate(self.worldstate) # needed because worldstate was never initialized before
00078         self.assertFalse(self.goal.is_valid(self.worldstate), 'Goal should not be valid yet')
00079 
00080     def testPlannerPos(self):
00081         print '==', self.testPlannerPos.__name__
00082         start_node = self.runner.update_and_plan(self.goal, introspection=True)
00083         print 'start_node found: ', start_node
00084         self.assertIsNotNone(start_node, 'There should be a plan')
00085         self.assertIsInstance(start_node, Node, 'Plan should be a Node')
00086         self.assertEqual(len(start_node.parent_actions_path_list), 3, 'Start Node should have three actions')
00087         self.assertEqual(len(start_node.parent_nodes_path_list), 3, 'Start Node should have three parent nodes')
00088 
00089         self.runner.execute_as_smach(start_node, introspection=True)
00090 
00091         import rospy
00092         rospy.sleep(5) # to latch introspection
00093 
00094 
00095     def testPlannerNeg(self):
00096         print '==', self.testPlannerNeg.__name__
00097         start_node = self.runner.update_and_plan(self.goal_inaccessible)
00098         print 'start_node found: ', start_node
00099         self.assertIsNone(start_node, 'There should be no plan')
00100 
00101 
00102     def tearDown(self):
00103         print 'memory was:', self.memory
00104 
00105 
00106 #@unittest.skip
00107 class TestIncrementer(unittest.TestCase):
00108 
00109     def setUp(self):
00110         self.runner = Runner()
00111 
00112         self.memory = self.runner.memory
00113         self.worldstate = self.runner.worldstate
00114 
00115         self.memory.set_value('memory.counter', 0)
00116 
00117         print self.memory
00118 
00119         Condition._conditions_dict.clear() # start every test without previous conditions
00120 
00121         Condition.add(MemoryCondition(self.memory, 'memory.counter'))
00122 
00123         Condition.initialize_worldstate(self.worldstate)
00124 
00125         self.actions = self.runner.actions
00126         self.actions.add(MemoryIncrementerAction(self.memory, 'memory.counter'))
00127 
00128         print Condition.print_dict()
00129 
00130         print self.actions
00131 
00132         self.goal = Goal([Precondition(Condition.get('memory.counter'), 3)])
00133 
00134         self.goal_inaccessible = Goal([Precondition(Condition.get('memory.counter'), -2)])
00135 
00136         print self.worldstate
00137 
00138         print self.runner
00139 
00140     def testGoals(self):
00141         print '==', self.testGoals.__name__
00142         Condition.initialize_worldstate(self.worldstate) # needed because worldstate was never initialized before
00143         self.assertFalse(self.goal.is_valid(self.worldstate), 'Goal should not be valid yet')
00144 
00145     def testPlannerPos(self):
00146         print '==', self.testPlannerPos.__name__
00147         start_node = self.runner.update_and_plan(self.goal)
00148         print 'start_node found: ', start_node
00149         self.assertIsNotNone(start_node, 'There should be a plan')
00150         self.assertIsInstance(start_node, Node, 'Plan should be a Node')
00151         self.assertEqual(len(start_node.parent_actions_path_list), 3, 'Plan should have three actions')
00152 
00153 
00154     def testPlannerPosUnneededCondition(self):
00155         Condition.add(MemoryCondition(self.memory, 'memory.unneeded'))
00156         Condition.initialize_worldstate(self.worldstate)
00157         print 'reinitialized worldstate with unneeded condition: ', self.worldstate
00158         self.testPlannerPos()
00159 
00160 
00161     def testPlannerNeg(self):
00162         print '==', self.testPlannerNeg.__name__
00163         start_node = self.runner.update_and_plan(self.goal_inaccessible)
00164         print 'start_node found: ', start_node
00165         self.assertIsNone(start_node, 'There should be no plan')
00166 
00167     def testPlannerNegPos(self):
00168         print '==', self.testPlannerNegPos.__name__
00169         self.actions.add(MemoryIncrementerAction(self.memory, 'memory.counter', -4))
00170         start_node = self.runner.update_and_plan(self.goal_inaccessible, introspection=True)
00171         print 'start_node found: ', start_node
00172         self.assertIsNotNone(start_node, 'There should be a plan')
00173         self.assertIsInstance(start_node, Node, 'Plan should be a Node')
00174         self.assertEqual(len(start_node.parent_actions_path_list), 3, 'Plan should have three actions')
00175 
00176         import rospy
00177         rospy.sleep(5) # to latch introspection
00178 
00179 
00180     @unittest.skip("deviation does not work yet") # FIXME: deviation does not work yet
00181     def testPlannerDeviation(self):
00182         print '==', self.testPlannerDeviation.__name__
00183         goal_dev = Goal([Precondition(Condition.get('memory.counter'), 2.05, 0.1)])
00184         start_node = self.runner.update_and_plan(goal_dev)
00185         print 'start_node found: ', start_node
00186         self.assertIsNotNone(start_node, 'There should be a plan')
00187         self.assertIsInstance(start_node, Node, 'Plan should be a Node')
00188         self.assertEqual(len(start_node.parent_actions_path_list), 2, 'Plan should have two actions')
00189 
00190 
00191     def testPlannerBig(self):
00192         print '==', self.testPlannerBig.__name__
00193         self.actions.add(MemoryIncrementerAction(self.memory, 'memory.counter', -4))
00194         self.actions.add(MemoryIncrementerAction(self.memory, 'memory.counter', 11))
00195         self.actions.add(MemoryIncrementerAction(self.memory, 'memory.counter', 3))
00196         goal_big = Goal([Precondition(Condition.get('memory.counter'), 23)])
00197         start_node = self.runner.update_and_plan(goal_big, introspection=True)
00198         print 'start_node found: ', start_node
00199 
00200         import rospy
00201         rospy.sleep(5) # to latch introspection
00202 
00203         self.assertIsNotNone(start_node, 'There should be a plan')
00204         self.assertIsInstance(start_node, Node, 'Plan should be a Node')
00205 
00206 
00207     def testRunnerMultipleGoals(self):
00208         print '==', self.testRunnerMultipleGoals.__name__
00209         goal_big = Goal([Precondition(Condition.get('memory.counter'), 23)])
00210         goals = [self.goal, self.goal_inaccessible, goal_big]
00211         self.runner.plan_and_execute_goals(goals)
00212 
00213 
00214     def tearDown(self):
00215         print 'memory was:', self.memory
00216 
00217 
00218 
00219 if __name__ == "__main__":
00220     #import sys;sys.argv = ['', 'Test.testName']
00221     unittest.main()


rgoap
Author(s): Felix Kolbe
autogenerated on Sun Oct 5 2014 23:53:02