test_simple_action_server_deadlock.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 #
00003 # Copyright (c) 2013, Miguel Sarabia
00004 # Imperial College London
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions are met:
00009 #
00010 #     * Redistributions of source code must retain the above copyright
00011 #       notice, this list of conditions and the following disclaimer.
00012 #     * Redistributions in binary form must reproduce the above copyright
00013 #       notice, this list of conditions and the following disclaimer in the
00014 #       documentation and/or other materials provided with the distribution.
00015 #     * Neither the name of Imperial College London nor the names of its
00016 #       contributors may be used to endorse or promote products derived from
00017 #       this software without specific prior written permission.
00018 #
00019 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 #
00031 
00032 
00033 class Constants:
00034     pkg = "actionlib"
00035     node = "test_simple_action_server_deadlock"
00036     topic = "deadlock"
00037     deadlock_timeout = 45  # in seconds
00038     shutdown_timeout = 2  # in seconds
00039     max_action_duration = 3
00040 
00041 import random
00042 import sys
00043 import threading
00044 import unittest
00045 
00046 import actionlib
00047 from actionlib.msg import TestAction
00048 import rosnode
00049 import rospy
00050 
00051 
00052 class DeadlockTest(unittest.TestCase):
00053 
00054     def test_deadlock(self):
00055         # Prepare condition (for safe preemption)
00056         self.condition = threading.Condition()
00057         self.last_execution_time = None
00058 
00059         # Prepare Simple Action Server
00060         self.action_server = actionlib.SimpleActionServer(
00061             Constants.topic,
00062             TestAction,
00063             execute_cb=self.execute_callback,
00064             auto_start=False)
00065 
00066         self.action_server.register_preempt_callback(self.preempt_callback)
00067         self.action_server.start()
00068 
00069         # Sleep for the amount specified
00070         rospy.sleep(Constants.deadlock_timeout)
00071 
00072         # Start actual tests
00073         running_nodes = set(rosnode.get_node_names())
00074         required_nodes = {
00075             "/deadlock_companion_1",
00076             "/deadlock_companion_2",
00077             "/deadlock_companion_3",
00078             "/deadlock_companion_4",
00079             "/deadlock_companion_5"}
00080 
00081         self.assertTrue(required_nodes.issubset(running_nodes),
00082             "Required companion nodes are not currently running")
00083 
00084         # Shutdown companions so that we can exit nicely
00085         termination_time = rospy.Time.now()
00086         rosnode.kill_nodes(required_nodes)
00087 
00088         rospy.sleep(Constants.shutdown_timeout)
00089 
00090         # Check last execution wasn't too long ago...
00091         self.assertIsNotNone(self.last_execution_time is None,
00092             "Execute Callback was never executed")
00093 
00094         time_since_last_execution = (
00095             termination_time - self.last_execution_time).to_sec()
00096 
00097         self.assertTrue(
00098             time_since_last_execution < 2 * Constants.max_action_duration,
00099             "Too long since last goal was executed; likely due to a deadlock")
00100 
00101     def execute_callback(self, goal):
00102         # Note down last_execution time
00103         self.last_execution_time = rospy.Time.now()
00104 
00105         # Determine duration of this action
00106         action_duration = random.uniform(0, Constants.max_action_duration)
00107 
00108         with self.condition:
00109             if not self.action_server.is_preempt_requested():
00110                 self.condition.wait(action_duration)
00111 
00112         if self.action_server.is_preempt_requested():
00113             self.action_server.set_preempted()
00114         else:
00115             self.action_server.set_succeeded()
00116 
00117     def preempt_callback(self):
00118         with self.condition:
00119             self.condition.notify()
00120 
00121 
00122 if __name__ == '__main__':
00123     import rostest
00124     rospy.init_node(Constants.node)
00125     rostest.rosrun(Constants.pkg, Constants.node, DeadlockTest)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Sun Oct 5 2014 22:02:55