test_simple_action_server_deadlock.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 #
3 # Copyright (c) 2013, Miguel Sarabia
4 # Imperial College London
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above copyright
13 # notice, this list of conditions and the following disclaimer in the
14 # documentation and/or other materials provided with the distribution.
15 # * Neither the name of Imperial College London nor the names of its
16 # contributors may be used to endorse or promote products derived from
17 # this software without specific prior written permission.
18 #
19 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.
30 
31 import random
32 import threading
33 import unittest
34 
35 import actionlib
36 from actionlib.msg import TestAction
37 import rosnode
38 import rospy
39 
40 
41 class Constants:
42  pkg = "actionlib"
43  node = "test_simple_action_server_deadlock"
44  topic = "deadlock"
45  deadlock_timeout = 45 # in seconds
46  shutdown_timeout = 2 # in seconds
47  max_action_duration = 3
48 
49 
50 class DeadlockTest(unittest.TestCase):
51 
52  def test_deadlock(self):
53  # Prepare condition (for safe preemption)
54  self.condition = threading.Condition()
55  self.last_execution_time = None
56 
57  # Prepare Simple Action Server
59  Constants.topic,
60  TestAction,
61  execute_cb=self.execute_callback,
62  auto_start=False)
63 
64  self.action_server.register_preempt_callback(self.preempt_callback)
65  self.action_server.start()
66 
67  # Sleep for the amount specified
68  rospy.sleep(Constants.deadlock_timeout)
69 
70  # Start actual tests
71  running_nodes = set(rosnode.get_node_names())
72  required_nodes = {
73  "/deadlock_companion_1",
74  "/deadlock_companion_2",
75  "/deadlock_companion_3",
76  "/deadlock_companion_4",
77  "/deadlock_companion_5"}
78 
79  self.assertTrue(
80  required_nodes.issubset(running_nodes),
81  "Required companion nodes are not currently running")
82 
83  # Shutdown companions so that we can exit nicely
84  termination_time = rospy.Time.now()
85  rosnode.kill_nodes(required_nodes)
86 
87  rospy.sleep(Constants.shutdown_timeout)
88 
89  # Check last execution wasn't too long ago...
90  self.assertIsNotNone(
91  self.last_execution_time is None,
92  "Execute Callback was never executed")
93 
94  time_since_last_execution = (
95  termination_time - self.last_execution_time).to_sec()
96 
97  self.assertTrue(
98  time_since_last_execution < 2 * Constants.max_action_duration,
99  "Too long since last goal was executed; likely due to a deadlock")
100 
101  def execute_callback(self, goal):
102  # Note down last_execution time
103  self.last_execution_time = rospy.Time.now()
104 
105  # Determine duration of this action
106  action_duration = random.uniform(0, Constants.max_action_duration)
107 
108  with self.condition:
109  if not self.action_server.is_preempt_requested():
110  self.condition.wait(action_duration)
111 
112  if self.action_server.is_preempt_requested():
113  self.action_server.set_preempted()
114  else:
115  self.action_server.set_succeeded()
116 
117  def preempt_callback(self):
118  with self.condition:
119  self.condition.notify()
120 
121 
122 if __name__ == '__main__':
123  import rostest
124  rospy.init_node(Constants.node)
125  rostest.rosrun(Constants.pkg, Constants.node, DeadlockTest)


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Mon Aug 24 2020 03:40:47