Skip to content

Commit

Permalink
rosmaster leaves sockets in CLOSE_WAIT state #610 (#834)
Browse files Browse the repository at this point in the history
  • Loading branch information
mikepurvis committed Jan 31, 2017
1 parent fbe9de2 commit cb356ef
Show file tree
Hide file tree
Showing 31 changed files with 160 additions and 114 deletions.
10 changes: 3 additions & 7 deletions clients/rospy/src/rospy/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,14 +56,10 @@
except ImportError:
import urlparse

try:
import xmlrpc.client as xmlrpcclient #Python 3.x
except ImportError:
import xmlrpclib as xmlrpcclient #Python 2.x

import rospkg

import rosgraph.roslogging
import rosgraph.xmlrpc

import rospy.exceptions
import rospy.rostime
Expand Down Expand Up @@ -534,12 +530,12 @@ def validator(param_value, caller_id):
def xmlrpcapi(uri):
"""
@return: instance for calling remote server or None if not a valid URI
@rtype: xmlrpclib.ServerProxy
@rtype: rosgraph.xmlrpc.ServerProxy
"""
if uri is None:
return None
uriValidate = urlparse.urlparse(uri)
if not uriValidate[0] or not uriValidate[1]:
return None
return xmlrpcclient.ServerProxy(uri)
return rosgraph.xmlrpc.ServerProxy(uri)

6 changes: 1 addition & 5 deletions clients/rospy/src/rospy/impl/tcpros_pubsub.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,7 @@
import threading
import time

try:
from xmlrpc.client import ServerProxy # Python 3.x
except ImportError:
from xmlrpclib import ServerProxy # Python 2.x

from rosgraph.xmlrpc import ServerProxy
from rospy.core import logwarn, logerr, logdebug, rospyerr
import rospy.exceptions
import rospy.names
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,13 @@
import time
import unittest
try:
from xmlrpc.client import Fault, ServerProxy
from xmlrpc.client import Fault
except ImportError:
from xmlrpclib import Fault, ServerProxy
from xmlrpclib import Fault

import rosunit
import rosgraph
from rosgraph.xmlrpc import ServerProxy

TCPROS = 'TCPROS'

Expand Down
5 changes: 1 addition & 4 deletions test/test_rosmaster/test/master.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,10 @@
import sys
import string
import time
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rospy
import rosgraph
from rosgraph.xmlrpc import ServerProxy

from rosclient import *

Expand Down
5 changes: 1 addition & 4 deletions test/test_rosmaster/test/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,10 @@
import sys
import string
import time
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rospy
import rosgraph
from rosgraph.xmlrpc import ServerProxy

from rosclient import *

Expand Down
6 changes: 2 additions & 4 deletions test/test_rosmaster/test/rosclient.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,12 +34,10 @@
# Revision $Id: test_embed_msg.py 1986 2008-08-26 23:57:56Z sfkwc $

import unittest
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rosgraph
from rosgraph.xmlrpc import ServerProxy


class TestRosClient(unittest.TestCase):

Expand Down
5 changes: 3 additions & 2 deletions test/test_rosmaster/test/testMaster.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,12 @@
import os, sys, getopt, traceback, logging, socket
import datetime, math, random
try:
from xmlrpc.client import DateTime, ServerProxy
from xmlrpc.client import DateTime
except ImportError:
from xmlrpclib import DateTime, ServerProxy
from xmlrpclib import DateTime
import unittest
import rospy
from rosgraph.xmlrpc import ServerProxy
from rostest import *
from testSlave import msMain

Expand Down
5 changes: 1 addition & 4 deletions test/test_rosmaster/test/testSlave.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,9 @@
import os
import sys
import string
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rospy
from rosgraph.xmlrpc import ServerProxy
from rostest import *

singletest = None
Expand Down
5 changes: 1 addition & 4 deletions test/test_rospy/test/rostest/test_deregister.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@

import rospy
import rostest
from rosgraph.xmlrpc import ServerProxy
from std_msgs.msg import String
from test_rospy.srv import EmptySrv

Expand All @@ -61,10 +62,6 @@ def callback(data):
print("message received", data.data)
_last_callback = data

try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

class TestDeregister(unittest.TestCase):

Expand Down
5 changes: 1 addition & 4 deletions test/test_rospy/test/rostest/test_sub_to_multiple_pubs.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,9 @@
import sys
import time
import unittest
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rosgraph
from rosgraph.xmlrpc import ServerProxy
import rospy
import rostest

Expand Down
5 changes: 1 addition & 4 deletions test/test_rospy/test/unit/test_rospy_core.py
Original file line number Diff line number Diff line change
Expand Up @@ -219,10 +219,7 @@ def test_xmlrpcapi(self):
self.assert_(rospy.core.xmlrpcapi('http://') is None)
api = rospy.core.xmlrpcapi('http://localhost:1234')
self.assert_(api is not None)
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy
from rosgraph.xmlrpc import ServerProxy
self.assert_(isinstance(api, ServerProxy))

called = None
Expand Down
1 change: 1 addition & 0 deletions tools/rosgraph/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend version_gte="0.5.78">catkin</buildtool_depend>

<run_depend>python-netifaces</run_depend>
<run_depend>python-requests</run_depend>
<run_depend>python-rospkg</run_depend>

<test_depend>python-mock</test_depend>
Expand Down
7 changes: 2 additions & 5 deletions tools/rosgraph/src/rosgraph/impl/graph.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,10 @@
import random
import logging
import traceback
try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy
import socket

import rosgraph.masterapi
from rosgraph.xmlrpc import ServerProxy

logger = logging.getLogger('rosgraph.graph')

Expand Down Expand Up @@ -371,7 +368,7 @@ def _node_refresh_businfo(self, node, api, bad_node=False):
@param node: node name
@type node: str
@param api: XML-RPC proxy
@type api: ServerProxy
@type api: rosgraph.xmlrpc.ServerProxy
@param bad_node: If True, node has connectivity issues and
should be treated differently
@type bad_node: bool
Expand Down
6 changes: 1 addition & 5 deletions tools/rosgraph/src/rosgraph/masterapi.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,10 @@
the Master API is changed.
"""

try:
from xmlrpc.client import ServerProxy # Python 3.x
except ImportError:
from xmlrpclib import ServerProxy # Python 2.x

from . names import make_caller_id
from . rosenv import get_master_uri
from . network import parse_http_host_and_port
from . xmlrpc import ServerProxy

class MasterException(Exception):
"""
Expand Down
63 changes: 63 additions & 0 deletions tools/rosgraph/src/rosgraph/transport.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
"""A replacement transport for Python xmlrpc library."""

try:
import xmlrpc.client as xmlrpc
except ImportError:
import xmlrpclib as xmlrpc

import socket
import requests
import urllib3.exceptions


class RequestsTransport(xmlrpc.Transport):
"""Drop in Transport for xmlrpclib that uses Requests instead of httplib"""

user_agent = "Python XMLRPC with Requests (python-requests.org)"

def __init__(self, scheme, use_datetime=0):
xmlrpc.Transport.__init__(self, use_datetime)
self._scheme = scheme

def request(self, host, handler, request_body, verbose=0):
"""Make a xmlrpc request."""
headers = {'User-Agent': self.user_agent, 'Content-Type': 'text/xml'}
url = '{scheme}://{host}{handler}'.format(scheme=self._scheme,
host=host,
handler=handler)
try:
resp = requests.post(url, data=request_body.encode('utf-8'),
headers=headers)
except requests.exceptions.Timeout:
raise socket.timeout('timed out')
except requests.RequestException as exc:
if isinstance(exc.args[0], urllib3.exceptions.HTTPError):
# Rethrow urllib3 exception.reason. That are e.g. socket.error
# Or other exceptions that the default xmlrpclib implementation
# would throw.
raise exc.args[0].reason
else:
# otherwise, rethrow the exc
# We could add more exception mappings here:
# - requests.exceptions.InvalidURL -> socket.gaierror?
# - requests.exceptions.InvalidSchema -> socket.gaierror?
raise exc
except (ValueError, Exception):
raise
else:
try:
resp.raise_for_status()
except requests.RequestException as exc:
raise xmlrpc.ProtocolError(url, resp.status_code,
str(exc), resp.headers)
else:
return self.parse_response(resp)

def parse_response(self, resp):
"""
Parse the xmlrpc response.
"""
p, u = self.getparser()
p.feed(resp.text)
p.close()
return u.close()
23 changes: 23 additions & 0 deletions tools/rosgraph/src/rosgraph/xmlrpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -59,12 +59,22 @@
from SimpleXMLRPCServer import SimpleXMLRPCServer #Python 2.x
from SimpleXMLRPCServer import SimpleXMLRPCRequestHandler #Python 2.x

try:
from xmlrpc.client import ServerProxy as _ServerProxy
except ImportError:
from xmlrpclib import ServerProxy as _ServerProxy
try:
from urllib.parse import splittype
except ImportError:
from urllib import splittype

try:
import socketserver
except ImportError:
import SocketServer as socketserver

import rosgraph.network
from rosgraph.transport import RequestsTransport

def isstring(s):
"""Small helper version to check an object is a string in a way that works
Expand All @@ -76,10 +86,23 @@ def isstring(s):
return isinstance(s, str)

class SilenceableXMLRPCRequestHandler(SimpleXMLRPCRequestHandler):
protocol_version = 'HTTP/1.1'

def log_message(self, format, *args):
if 0:
SimpleXMLRPCRequestHandler.log_message(self, format, *args)

class ServerProxy(_ServerProxy):
def __init__(self, uri, transport=None, encoding=None, verbose=0,
allow_none=0, use_datetime=0):
if transport is None:
scheme, _ = splittype(uri)
transport = RequestsTransport(scheme)

_ServerProxy.__init__(self, uri, transport=transport, encoding=encoding,
verbose=verbose, allow_none=allow_none,
use_datetime=use_datetime)

class ThreadingXMLRPCServer(socketserver.ThreadingMixIn, SimpleXMLRPCServer):
"""
Adds ThreadingMixin to SimpleXMLRPCServer to support multiple concurrent
Expand Down
1 change: 1 addition & 0 deletions tools/roslaunch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
<run_depend version_gte="1.0.37">python-rospkg</run_depend>
<run_depend>python-yaml</run_depend>
<run_depend>rosclean</run_depend>
<run_depend>rosgraph</run_depend>
<run_depend>rosgraph_msgs</run_depend>
<run_depend>roslib</run_depend>
<run_depend version_gte="1.11.16">rosmaster</run_depend>
Expand Down
7 changes: 4 additions & 3 deletions tools/roslaunch/src/roslaunch/core.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,16 @@
import socket
import sys
try:
from xmlrpc.client import MultiCall, ServerProxy
from xmlrpc.client import MultiCall
except ImportError:
from xmlrpclib import MultiCall, ServerProxy
from xmlrpclib import MultiCall

import rospkg

import rosgraph
import rosgraph.names
import rosgraph.network
from rosgraph.xmlrpc import ServerProxy

from xml.sax.saxutils import escape
try:
Expand Down Expand Up @@ -288,7 +289,7 @@ def __eq__(self, m2):

def get(self):
"""
:returns:: XMLRPC proxy for communicating with master, ``xmlrpc.client.ServerProxy``
:returns:: XMLRPC proxy for communicating with master, ``rosgraph.xmlrpc.ServerProxy``
"""
return ServerProxy(self.uri)

Expand Down
2 changes: 1 addition & 1 deletion tools/roslaunch/src/roslaunch/launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -433,7 +433,7 @@ def _check_and_set_run_id(self, param_server, run_id):
@param default_run_id: run_id to use if value is not set
@type default_run_id: str
@param param_server: parameter server proxy
@type param_server: xmlrpclib.ServerProxy
@type param_server: rosgraph.xmlrpc.ServerProxy
"""
code, _, val = param_server.hasParam(_ID, '/run_id')
if code == 1 and not val:
Expand Down
6 changes: 1 addition & 5 deletions tools/roslaunch/src/roslaunch/netapi.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,9 @@
Convience methods for manipulating XML-RPC APIs
"""

try:
from xmlrpc.client import ServerProxy
except ImportError:
from xmlrpclib import ServerProxy

import rosgraph
import rosgraph.network
from rosgraph.xmlrpc import ServerProxy

_ID = '/roslaunch_netapi'
def get_roslaunch_uris():
Expand Down
Loading

0 comments on commit cb356ef

Please sign in to comment.