Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Avoid waiting in loops #164

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 15 additions & 11 deletions actionlib/src/actionlib/simple_action_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
# Author: Alexander Sorokin.
# Based on C++ simple_action_server.h by Eitan Marder-Eppstein
import rospy
import rospy.core
import threading
import traceback

Expand Down Expand Up @@ -70,7 +71,6 @@ def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True):
self.preempt_callback = None

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
Expand All @@ -91,11 +91,17 @@ def __init__(self, name, ActionSpec, execute_cb=None, auto_start=True):

# create the action server
self.action_server = ActionServer(name, ActionSpec, self.internal_goal_callback, self.internal_preempt_callback, auto_start)
rospy.core.add_shutdown_hook(self.request_shutdown)

def request_shutdown(self, _):
with self.execute_condition:
self.execute_condition.notify()

def __del__(self):
if hasattr(self, 'execute_callback') and self.execute_callback:
with self.terminate_mutex:
self.need_to_terminate = True
self.need_to_terminate = True
with self.execute_condition:
self.execute_condition.notify()

assert(self.execute_thread)
self.execute_thread.join()
Expand Down Expand Up @@ -263,12 +269,13 @@ def internal_preempt_callback(self, preempt):

## @brief Called from a separate thread to call blocking execute calls
def executeLoop(self):
loop_duration = rospy.Duration.from_sec(.1)

while (not rospy.is_shutdown()):
with self.terminate_mutex:
if (self.need_to_terminate):
break
while not rospy.core.is_shutdown_requested():
with self.execute_condition:
self.execute_condition.wait()

if self.need_to_terminate or rospy.core.is_shutdown_requested():
break

# the following checks (is_active, is_new_goal_available)
# are performed without locking
Expand Down Expand Up @@ -297,6 +304,3 @@ def executeLoop(self):
rospy.logerr("Exception in your execute callback: %s\n%s", str(ex),
traceback.format_exc())
self.set_aborted(None, "Exception in execute callback: %s" % str(ex))

with self.execute_condition:
self.execute_condition.wait(loop_duration.to_sec())