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

[rospy] made get_published_topics threadsafe #958

Merged
merged 2 commits into from
Jan 10, 2017
Merged
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
6 changes: 3 additions & 3 deletions clients/rospy/src/rospy/msproxy.py
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,6 @@ def __init__(self, uri):
self._lock = Lock()

def __getattr__(self, key): #forward api calls to target
with self._lock:
f = getattr(self.target, key)
if key in _master_arg_remap:
remappings = _master_arg_remap[key]
else:
Expand All @@ -103,7 +101,9 @@ def wrappedF(*args, **kwds):
i = i + 1 #callerId does not count
#print "Remap %s => %s"%(args[i], rospy.names.resolve_name(args[i]))
args[i] = rospy.names.resolve_name(args[i])
return f(*args, **kwds)
with self._lock:
f = getattr(self.target, key)
return f(*args, **kwds)
return wrappedF

def __getitem__(self, key):
Expand Down