Skip to content

Commit

Permalink
Use thread local storage for caching instances of ServerProxy (#1732)
Browse files Browse the repository at this point in the history
xmlrpc.client.ServerProxy is not thread safe. See
https://bugs.python.org/issue6907

The symptom of this bug is exceptions in the publisherUpdate
logged in the master.log. For example:

[rosmaster.threadpool][ERROR] : Traceback (most recent call last):
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosmaster/threadpool.py", line 218, in run
    result = cmd(*args)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosmaster/master_api.py", line 210, in publisher_update_task
    ret = xmlrpcapi(api).publisherUpdate('/master', topic, pub_uris)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosmaster/util.py", line 68, in xmlrpcapi
    close_half_closed_sockets()
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rosmaster/util.py", line 79, in close_half_closed_sockets
    state = transport._connection[1].sock.getsockopt(socket.SOL_TCP, socket.TCP_INFO)
  File "/usr/lib/python2.7/socket.py", line 228, in meth
    return getattr(self._sock,name)(*args)
  File "/usr/lib/python2.7/socket.py", line 174, in _dummy
    raise error(EBADF, 'Bad file descriptor')
error: [Errno 9] Bad file descriptor

Some subscribers get the update but some do not. For example, the topic
is recorded in a rosbag but not received by nodes that depend on it.

Issue: #1523
  • Loading branch information
johnfettig authored and dirk-thomas committed Aug 4, 2020
1 parent 5153a75 commit f1d4a11
Showing 1 changed file with 8 additions and 7 deletions.
15 changes: 8 additions & 7 deletions tools/rosmaster/src/rosmaster/util.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,9 @@

import errno
import socket
import threading

_proxies = {} #cache ServerProxys
_proxies = threading.local() #cache ServerProxys
def xmlrpcapi(uri):
"""
@return: instance for calling remote server or None if not a valid URI
Expand All @@ -63,16 +64,16 @@ def xmlrpcapi(uri):
uriValidate = urlparse(uri)
if not uriValidate[0] or not uriValidate[1]:
return None
if not uri in _proxies:
_proxies[uri] = ServerProxy(uri)
if not uri in _proxies.__dict__:
_proxies.__dict__[uri] = ServerProxy(uri)
close_half_closed_sockets()
return _proxies[uri]
return _proxies.__dict__[uri]


def close_half_closed_sockets():
if not hasattr(socket, 'TCP_INFO'):
return
for proxy in _proxies.values():
for proxy in _proxies.__dict__.values():
transport = proxy("transport")
if transport._connection and transport._connection[1] is not None and transport._connection[1].sock is not None:
try:
Expand All @@ -86,5 +87,5 @@ def close_half_closed_sockets():


def remove_server_proxy(uri):
if uri in _proxies:
del _proxies[uri]
if uri in _proxies.__dict__:
del _proxies.__dict__[uri]

0 comments on commit f1d4a11

Please sign in to comment.