Skip to content

Commit

Permalink
fix deadlock in simple_action_server.py (fix #4)
Browse files Browse the repository at this point in the history
  • Loading branch information
dirk-thomas committed Aug 5, 2013
1 parent 7a0ba3e commit ab25df9
Showing 1 changed file with 23 additions and 16 deletions.
39 changes: 23 additions & 16 deletions src/actionlib/simple_action_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,11 @@ def __init__(self, name, ActionSpec, execute_cb = None, auto_start = True):

self.need_to_terminate = False
self.terminate_mutex = threading.RLock();

# since the internal_goal/preempt_callbacks are invoked from the
# ActionServer while holding the self.action_server.lock
# self.lock must always be locked after the action server lock
# to avoid an inconsistent lock acquisition order
self.lock = threading.RLock();

self.execute_condition = threading.Condition(self.lock);
Expand Down Expand Up @@ -108,7 +113,7 @@ def __del__(self):
## sure the new goal does not have a pending preempt request.
## @return A shared_ptr to the new goal.
def accept_new_goal(self):
with self.lock:
with self.action_server.lock, self.lock:
if not self.new_goal or not self.next_goal.get_goal():
rospy.logerr("Attempting to accept the next goal when a new goal is not available");
return None;
Expand Down Expand Up @@ -156,15 +161,15 @@ def is_active(self):
## @brief Sets the status of the active goal to succeeded
## @param result An optional result to send back to any clients of the goal
def set_succeeded(self,result=None, text=""):
with self.lock:
with self.action_server.lock, self.lock:
if not result:
result=self.get_default_result();
self.current_goal.set_succeeded(result, text);

## @brief Sets the status of the active goal to aborted
## @param result An optional result to send back to any clients of the goal
def set_aborted(self, result = None, text=""):
with self.lock:
with self.action_server.lock, self.lock:
if not result:
result=self.get_default_result();
self.current_goal.set_aborted(result, text);
Expand All @@ -183,7 +188,7 @@ def get_default_result(self):
def set_preempted(self,result=None, text=""):
if not result:
result=self.get_default_result();
with self.lock:
with self.action_server.lock, self.lock:
rospy.logdebug("Setting the current goal as canceled");
self.current_goal.set_canceled(result, text);

Expand Down Expand Up @@ -275,19 +280,21 @@ def executeLoop(self):
if (self.need_to_terminate):
break;

shall_run=False;
with self.lock:
if (self.is_active()):
rospy.logerr("Should never reach this code with an active goal");
# the following checks (is_active, is_new_goal_available)
# are performed without locking
# the worst thing that might happen in case of a race
# condition is a warning/error message on the console
if (self.is_active()):
rospy.logerr("Should never reach this code with an active goal");
return

if (self.is_new_goal_available()):
# accept_new_goal() is performing its own locking
goal = self.accept_new_goal();
if not self.execute_callback:
rospy.logerr("execute_callback_ must exist. This is a bug in SimpleActionServer");
return
elif (self.is_new_goal_available()):
goal = self.accept_new_goal();
if not self.execute_callback:
rospy.logerr("execute_callback_ must exist. This is a bug in SimpleActionServer");
return
shall_run=True

if shall_run:

try:
self.execute_callback(goal)

Expand Down

0 comments on commit ab25df9

Please sign in to comment.