From 5c8997e0856b796fb8c813378f0c87304b0d8a4e Mon Sep 17 00:00:00 2001 From: Jannik Abbenseth Date: Tue, 10 Jan 2017 18:48:02 +0100 Subject: [PATCH] [rospy] made get_published_topics threadsafe (#958) * [rospy] made get_published_topics threadsafe --- clients/rospy/src/rospy/msproxy.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/clients/rospy/src/rospy/msproxy.py b/clients/rospy/src/rospy/msproxy.py index c44176c8c1..936f2215b6 100644 --- a/clients/rospy/src/rospy/msproxy.py +++ b/clients/rospy/src/rospy/msproxy.py @@ -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: @@ -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):