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

fix 206: introduce lock to prevent send_goal race condition #207

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
12 changes: 7 additions & 5 deletions actionlib/src/actionlib/simple_action_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
# Author: Stuart Glaser
import rospy
import threading

from actionlib_msgs.msg import GoalStatus
from actionlib.action_client import ActionClient, CommState, get_name_of_constant

Expand All @@ -56,6 +55,7 @@ def __init__(self, ns, ActionSpec):
self.simple_state = SimpleGoalState.DONE
self.gh = None
self.done_condition = threading.Condition()
self.lock = threading.RLock() # fix #206

## @brief Blocks until the action server connects to this client
##
Expand Down Expand Up @@ -89,7 +89,8 @@ def send_goal(self, goal, done_cb=None, active_cb=None, feedback_cb=None):
self.feedback_cb = feedback_cb

self.simple_state = SimpleGoalState.PENDING
self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback)
with self.lock:
self.gh = self.action_client.send_goal(goal, self._handle_transition, self._handle_feedback)

## @brief Sends a goal to the ActionServer, waits for the goal to complete, and preempts goal is necessary
##
Expand Down Expand Up @@ -213,9 +214,10 @@ def stop_tracking_goal(self):

def _handle_transition(self, gh):

if gh != self.gh:
rospy.logerr("Got a transition callback on a goal handle that we're not tracking")
return
with self.lock:
if gh != self.gh:
rospy.logerr("Got a transition callback on a goal handle that we're not tracking")
return

comm_state = gh.get_comm_state()

Expand Down