Skip to content

Commit

Permalink
Merge pull request #9 from miguelsdc/deadlock_test2
Browse files Browse the repository at this point in the history
Python Simple Action Server Deadlock Test [2nd attempt]
  • Loading branch information
dirk-thomas committed Aug 5, 2013
2 parents a36553f + 2b6fb0a commit c957ddd
Show file tree
Hide file tree
Showing 5 changed files with 218 additions and 0 deletions.
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -31,4 +31,6 @@
<run_depend>rospy</run_depend>
<run_depend>rostest</run_depend>
<run_depend>std_msgs</run_depend>

<test_depend>rosnode</test_depend>
</package>
1 change: 1 addition & 0 deletions test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ add_rostest(test_python_server2.launch)
add_rostest(test_python_server3.launch)
add_rostest(test_python_simple_server.launch)
add_rostest(test_exercise_simple_clients.launch)
add_rostest(test_simple_action_server_deadlock_python.launch)

catkin_add_gtest(actionlib-destruction_guard_test destruction_guard_test.cpp)
if(TARGET actionlib-destruction_guard_test)
Expand Down
79 changes: 79 additions & 0 deletions test/simple_action_server_deadlock_companion.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
#! /usr/bin/env python
#
# Copyright (c) 2013, Miguel Sarabia
# Imperial College London
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of Imperial College London nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#


class Constants:
node = "simple_action_server_deadlock_companion"
topic = "deadlock"
max_action_duration = 3

import random

import actionlib
from actionlib.msg import TestAction, TestGoal
from actionlib_msgs.msg import GoalStatus
import rospy


class DeadlockCompanion:

def __init__(self):
# Seed random with fully resolved name of node and current time
random.seed(rospy.get_name() + str(rospy.Time.now().to_sec()))

# Create actionlib client
self.action_client = actionlib.SimpleActionClient(
Constants.topic,
TestAction)

def run(self):
while not rospy.is_shutdown():
# Send dummy goal
self.action_client.send_goal(TestGoal())

# Wait for a random amount of time
action_duration = random.uniform(0, Constants.max_action_duration)
self.action_client.wait_for_result(rospy.Duration(action_duration))

state = self.action_client.get_state()
if state == GoalStatus.ACTIVE or state == GoalStatus.PENDING:
self.action_client.cancel_goal()


if __name__ == '__main__':
rospy.init_node(Constants.node)
try:
companion = DeadlockCompanion()
companion.run()
except (KeyboardInterrupt, SystemExit):
raise
except:
pass
125 changes: 125 additions & 0 deletions test/test_simple_action_server_deadlock.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
#! /usr/bin/env python
#
# Copyright (c) 2013, Miguel Sarabia
# Imperial College London
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions are met:
#
# * Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# * Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in the
# documentation and/or other materials provided with the distribution.
# * Neither the name of Imperial College London nor the names of its
# contributors may be used to endorse or promote products derived from
# this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#


class Constants:
pkg = "actionlib"
node = "test_simple_action_server_deadlock"
topic = "deadlock"
deadlock_timeout = 45 # in seconds
shutdown_timeout = 2 # in seconds
max_action_duration = 3

import random
import sys
import threading
import unittest

import actionlib
from actionlib.msg import TestAction
import rosnode
import rospy


class DeadlockTest(unittest.TestCase):

def test_deadlock(self):
# Prepare condition (for safe preemption)
self.condition = threading.Condition()
self.last_execution_time = None

# Prepare Simple Action Server
self.action_server = actionlib.SimpleActionServer(
Constants.topic,
TestAction,
execute_cb=self.execute_callback,
auto_start=False)

self.action_server.register_preempt_callback(self.preempt_callback)
self.action_server.start()

# Sleep for the amount specified
rospy.sleep(Constants.deadlock_timeout)

# Start actual tests
running_nodes = set(rosnode.get_node_names())
required_nodes = {
"/deadlock_companion_1",
"/deadlock_companion_2",
"/deadlock_companion_3",
"/deadlock_companion_4",
"/deadlock_companion_5"}

self.assertTrue(required_nodes.issubset(running_nodes),
"Required companion nodes are not currently running")

# Shutdown companions so that we can exit nicely
termination_time = rospy.Time.now()
rosnode.kill_nodes(required_nodes)

rospy.sleep(Constants.shutdown_timeout)

# Check last execution wasn't too long ago...
self.assertIsNotNone(self.last_execution_time is None,
"Execute Callback was never executed")

time_since_last_execution = (
termination_time - self.last_execution_time).to_sec()

self.assertTrue(
time_since_last_execution < 2 * Constants.max_action_duration,
"Too long since last goal was executed; likely due to a deadlock")

def execute_callback(self, goal):
# Note down last_execution time
self.last_execution_time = rospy.Time.now()

# Determine duration of this action
action_duration = random.uniform(0, Constants.max_action_duration)

with self.condition:
if not self.action_server.is_preempt_requested():
self.condition.wait(action_duration)

if self.action_server.is_preempt_requested():
self.action_server.set_preempted()
else:
self.action_server.set_succeeded()

def preempt_callback(self):
with self.condition:
self.condition.notify()


if __name__ == '__main__':
import rostest
rospy.init_node(Constants.node)
rostest.rosrun(Constants.pkg, Constants.node, DeadlockTest)
11 changes: 11 additions & 0 deletions test/test_simple_action_server_deadlock_python.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
<launch>
<!-- Companion nodes -->
<node pkg="actionlib" type="simple_action_server_deadlock_companion.py" name="deadlock_companion_1" required="false"/>
<node pkg="actionlib" type="simple_action_server_deadlock_companion.py" name="deadlock_companion_2" required="false"/>
<node pkg="actionlib" type="simple_action_server_deadlock_companion.py" name="deadlock_companion_3" required="false"/>
<node pkg="actionlib" type="simple_action_server_deadlock_companion.py" name="deadlock_companion_4" required="false"/>
<node pkg="actionlib" type="simple_action_server_deadlock_companion.py" name="deadlock_companion_5" required="false"/>

<!-- Actual testing node -->
<test pkg="actionlib" type="test_simple_action_server_deadlock.py" test-name="test_simple_action_server_deadlock" />
</launch>

0 comments on commit c957ddd

Please sign in to comment.