From ace5ec5535d2297d6dc5501b8d98ae9ba7753e38 Mon Sep 17 00:00:00 2001 From: Kartik Mohta Date: Sun, 5 Nov 2017 23:38:49 -0500 Subject: [PATCH] Add Python3 compatibility (#300) * First pass at Python 3 compatibility * message_conversion: Only call encode on a Python2 str or bytes type * protocol.py: Changes for dict in Python3. Compatible with Python 2 too. * More Python 3 fixes, all tests pass * Move definition of string_types to rosbridge_library.util --- rosapi/src/rosapi/objectutils.py | 68 +++++++++---------- .../capabilities/advertise.py | 5 +- .../capabilities/advertise_service.py | 3 +- .../capabilities/call_service.py | 7 +- .../rosbridge_library/capabilities/publish.py | 5 +- .../capabilities/service_response.py | 5 +- .../capabilities/subscribe.py | 10 +-- .../internal/message_conversion.py | 54 ++++++++++----- .../internal/pngcompression.py | 2 +- .../rosbridge_library/internal/publishers.py | 2 +- .../rosbridge_library/internal/ros_loader.py | 2 +- .../src/rosbridge_library/protocol.py | 12 ++-- .../rosbridge_library/rosbridge_protocol.py | 5 +- .../src/rosbridge_library/util/__init__.py | 7 ++ .../test/capabilities/test_subscribe.py | 2 +- ...test_non-ros_service_client_complex-srv.py | 27 ++++---- ...test_non-ros_service_server_complex-srv.py | 37 +++++----- .../test_non-ros_service_client_fragmented.py | 27 ++++---- .../test_non-ros_service_server_fragmented.py | 39 +++++------ .../test_publisher_consistency_listener.py | 5 +- .../subscribers/test_multi_subscriber.py | 4 +- .../test_subscription_modifiers.py | 22 +++--- .../test/internal/test_compression.py | 4 +- .../test/internal/test_message_conversion.py | 31 ++++++--- .../test/internal/test_services.py | 22 +++--- rosbridge_server/scripts/rosbridge_tcp.py | 39 ++++++----- rosbridge_server/scripts/rosbridge_udp.py | 17 ++--- .../scripts/rosbridge_websocket.py | 21 +++--- .../src/rosbridge_server/__init__.py | 7 +- .../src/rosbridge_server/tcp_handler.py | 7 +- .../src/rosbridge_server/udp_handler.py | 3 +- 31 files changed, 282 insertions(+), 219 deletions(-) diff --git a/rosapi/src/rosapi/objectutils.py b/rosapi/src/rosapi/objectutils.py index 8cc27e410..4b301ad92 100644 --- a/rosapi/src/rosapi/objectutils.py +++ b/rosapi/src/rosapi/objectutils.py @@ -31,14 +31,12 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. -from string import find - from rosbridge_library.internal import ros_loader # Keep track of atomic types and special types atomics = ['bool', 'byte','int8', 'uint8', 'int16', 'uint16', 'int32', 'uint32', 'int64', 'uint64', 'float32', 'float64', 'string'] specials = ['time', 'duration'] - + def get_typedef(type): """ A typedef is a dict containing the following fields: @@ -46,18 +44,18 @@ def get_typedef(type): - string[] fieldnames - string[] fieldtypes - int[] fieldarraylen - - string[] examples + - string[] examples get_typedef will return a typedef dict for the specified message type """ if type in atomics: # Atomics don't get a typedef - return None - + return None + if type in specials: # Specials get their type def mocked up return _get_special_typedef(type) - + # Fetch an instance and return its typedef - instance = ros_loader.get_message_instance(type) + instance = ros_loader.get_message_instance(type) return _get_typedef(instance) def get_service_request_typedef(servicetype): @@ -68,7 +66,7 @@ def get_service_request_typedef(servicetype): def get_service_response_typedef(servicetype): """ Returns a typedef dict for the service response class for the specified service type """ - # Get an instance of the service response class and return its typedef + # Get an instance of the service response class and return its typedef instance = ros_loader.get_service_response_instance(servicetype) return _get_typedef(instance) @@ -82,7 +80,7 @@ def get_service_request_typedef_recursive(servicetype): # Get an instance of the service request class and get its typedef instance = ros_loader.get_service_request_instance(servicetype) typedef = _get_typedef(instance) - + # Return the list of sub-typedefs return _get_subtypedefs_recursive(typedef, []) @@ -91,7 +89,7 @@ def get_service_response_typedef_recursive(servicetype): # Get an instance of the service response class and get its typedef instance = ros_loader.get_service_response_instance(servicetype) typedef = _get_typedef(instance) - + # Return the list of sub-typedefs return _get_subtypedefs_recursive(typedef, []) @@ -99,16 +97,16 @@ def _get_typedef(instance): """ Gets a typedef dict for the specified instance """ if instance is None or not hasattr(instance, "__slots__") or not hasattr(instance, "_slot_types"): return None - + fieldnames = [] fieldtypes = [] fieldarraylen = [] examples = [] for i in xrange(len(instance.__slots__)): # Pull out the name - name = instance.__slots__[i] + name = instance.__slots__[i] fieldnames.append(name) - + # Pull out the type and determine whether it's an array field_type = instance._slot_types[i] arraylen = -1 @@ -117,15 +115,15 @@ def _get_typedef(instance): arraylen = 0 field_type = field_type[:-2] else: - split = find(field_type, '[') + split = field_type.find('[') arraylen = int(field_type[split+1:-1]) field_type = field_type[:split] fieldarraylen.append(arraylen) - + # Get the fully qualified type field_instance = getattr(instance, name) fieldtypes.append(_type_name(field_type, field_instance)) - + # Set the example as appropriate example = field_instance if arraylen>=0: @@ -133,7 +131,7 @@ def _get_typedef(instance): elif field_type not in atomics: example = {} examples.append(str(example)) - + typedef = { "type": _type_name_from_instance(instance), "fieldnames": fieldnames, @@ -141,9 +139,9 @@ def _get_typedef(instance): "fieldarraylen": fieldarraylen, "examples": examples } - + return typedef - + def _get_special_typedef(type): example = None if type=="time" or type=="duration": @@ -161,43 +159,43 @@ def _get_typedefs_recursive(type, typesseen): if type in typesseen: # Don't put a type if it's already been seen return [] - + # Note that we have now seen this type typesseen.append(type) - + # Get the typedef for this type and make sure it's not None typedef = get_typedef(type) - + return _get_subtypedefs_recursive(typedef, typesseen) - + def _get_subtypedefs_recursive(typedef, typesseen): if typedef is None: return [] - + # Create the list of subtypes and get the typedefs for fields typedefs = [ typedef ] for fieldtype in typedef["fieldtypes"]: typedefs = typedefs + _get_typedefs_recursive(fieldtype, typesseen) - + return typedefs def _type_name(type, instance): - """ given a short type, and an object instance of that type, - determines and returns the fully qualified type """ + """ given a short type, and an object instance of that type, + determines and returns the fully qualified type """ # The fully qualified type of atomic and special types is just their original name if type in atomics or type in specials: return type - + # If the instance is a list, then we can get no more information from the instance. # However, luckily, the 'type' field for list types is usually already inflated to the full type. if isinstance(instance, list): return type - - # Otherwise, the type will come from the module and class name of the instance + + # Otherwise, the type will come from the module and class name of the instance return _type_name_from_instance(instance) - + def _type_name_from_instance(instance): mod = instance.__module__ - type = mod[0:find(mod, '.')]+"/"+instance.__class__.__name__ - return type - + type = mod[0:mod.find('.')]+"/"+instance.__class__.__name__ + return type + diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py index 78fa01c69..7d76c8aa4 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise.py @@ -34,6 +34,7 @@ import fnmatch from rosbridge_library.capability import Capability from rosbridge_library.internal.publishers import manager +from rosbridge_library.util import string_types class Registration(): @@ -73,8 +74,8 @@ def is_empty(self): class Advertise(Capability): - advertise_msg_fields = [(True, "topic", (str, unicode)), (True, "type", (str, unicode))] - unadvertise_msg_fields = [(True, "topic", (str, unicode))] + advertise_msg_fields = [(True, "topic", string_types), (True, "type", string_types)] + unadvertise_msg_fields = [(True, "topic", string_types)] topics_glob = None diff --git a/rosbridge_library/src/rosbridge_library/capabilities/advertise_service.py b/rosbridge_library/src/rosbridge_library/capabilities/advertise_service.py index 588545919..5e54ccf20 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/advertise_service.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/advertise_service.py @@ -1,6 +1,7 @@ from rosbridge_library.internal.ros_loader import get_service_class from rosbridge_library.internal import message_conversion from rosbridge_library.capability import Capability +from rosbridge_library.util import string_types import fnmatch import rospy import time @@ -49,7 +50,7 @@ def handle_request(self, req): class AdvertiseService(Capability): - advertise_service_msg_fields = [(True, "service", (str, unicode)), (True, "type", (str, unicode))] + advertise_service_msg_fields = [(True, "service", string_types), (True, "type", string_types)] def __init__(self, protocol): # Call superclass constructor diff --git a/rosbridge_library/src/rosbridge_library/capabilities/call_service.py b/rosbridge_library/src/rosbridge_library/capabilities/call_service.py index 93bf231e7..b501b92da 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/call_service.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/call_service.py @@ -34,13 +34,14 @@ from functools import partial from rosbridge_library.capability import Capability from rosbridge_library.internal.services import ServiceCaller +from rosbridge_library.util import string_types class CallService(Capability): - call_service_msg_fields = [(True, "service", (str, unicode)), + call_service_msg_fields = [(True, "service", string_types), (False, "fragment_size", (int, type(None))), - (False, "compression", (str, unicode))] + (False, "compression", string_types)] services_glob = None @@ -77,7 +78,7 @@ def call_service(self, message): return else: self.protocol.log("debug", "No service security glob, not checking service call.") - + # Check for deprecated service ID, eg. /rosbridge/topics#33 cid = extract_id(service, cid) diff --git a/rosbridge_library/src/rosbridge_library/capabilities/publish.py b/rosbridge_library/src/rosbridge_library/capabilities/publish.py index 844f4d764..d755d98a4 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/publish.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/publish.py @@ -34,11 +34,12 @@ import fnmatch from rosbridge_library.capability import Capability from rosbridge_library.internal.publishers import manager +from rosbridge_library.util import string_types class Publish(Capability): - publish_msg_fields = [(True, "topic", (str, unicode))] + publish_msg_fields = [(True, "topic", string_types)] topics_glob = None @@ -83,7 +84,7 @@ def publish(self, message): # Publish the message manager.publish(client_id, topic, msg, latch=latch, queue_size=queue_size) - + def finish(self): client_id = self.protocol.client_id for topic in self._published: diff --git a/rosbridge_library/src/rosbridge_library/capabilities/service_response.py b/rosbridge_library/src/rosbridge_library/capabilities/service_response.py index 4a7f539f7..870a2aa14 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/service_response.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/service_response.py @@ -1,12 +1,13 @@ from rosbridge_library.capability import Capability from rosbridge_library.internal import ros_loader, message_conversion +from rosbridge_library.util import string_types class ServiceResponse(Capability): service_response_msg_fields = [ - (True, "service", (str, unicode)), (False, "id", (str, unicode)), - (False, "values", (str, unicode)), (True, "result", bool) + (True, "service", string_types), (False, "id", string_types), + (False, "values", string_types), (True, "result", bool) ] def __init__(self, protocol): diff --git a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py index cb8d4bf82..8cef70696 100644 --- a/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py +++ b/rosbridge_library/src/rosbridge_library/capabilities/subscribe.py @@ -47,6 +47,8 @@ except ImportError: from json import dumps +from rosbridge_library.util import string_types + class Subscription(): """ Keeps track of the clients multiple calls to subscribe. @@ -180,10 +182,10 @@ def f(fieldname): class Subscribe(Capability): - subscribe_msg_fields = [(True, "topic", (str, unicode)), (False, "type", (str, unicode)), + subscribe_msg_fields = [(True, "topic", string_types), (False, "type", string_types), (False, "throttle_rate", int), (False, "fragment_size", int), - (False, "queue_length", int), (False, "compression", (str, unicode))] - unsubscribe_msg_fields = [(True, "topic", (str, unicode))] + (False, "queue_length", int), (False, "compression", string_types)] + unsubscribe_msg_fields = [(True, "topic", string_types)] topics_glob = None @@ -242,7 +244,7 @@ def subscribe(self, msg): def unsubscribe(self, msg): # Pull out the ID sid = msg.get("id", None) - + self.basic_type_check(msg, self.unsubscribe_msg_fields) topic = msg["topic"] diff --git a/rosbridge_library/src/rosbridge_library/internal/message_conversion.py b/rosbridge_library/src/rosbridge_library/internal/message_conversion.py index 17859e6cd..c315588cb 100644 --- a/rosbridge_library/src/rosbridge_library/internal/message_conversion.py +++ b/rosbridge_library/src/rosbridge_library/internal/message_conversion.py @@ -31,6 +31,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from __future__ import print_function import roslib import rospy @@ -42,18 +43,34 @@ from base64 import standard_b64encode, standard_b64decode import bson -type_map = { - "bool": ["bool"], - "int": ["int8", "byte", "uint8", "char", - "int16", "uint16", "int32", "uint32", - "int64", "uint64", "float32", "float64"], - "float": ["float32", "float64"], - "str": ["string"], - "unicode": ["string"], - "long": ["int64", "uint64"] -} -primitive_types = [bool, int, long, float] -string_types = [str, unicode] +from rosbridge_library.util import string_types + +import sys +if sys.version_info >= (3, 0): + type_map = { + "bool": ["bool"], + "int": ["int8", "byte", "uint8", "char", + "int16", "uint16", "int32", "uint32", + "int64", "uint64", "float32", "float64"], + "float": ["float32", "float64"], + "str": ["string"] + } + primitive_types = [bool, int, float] + python2 = False +else: + type_map = { + "bool": ["bool"], + "int": ["int8", "byte", "uint8", "char", + "int16", "uint16", "int32", "uint32", + "int64", "uint64", "float32", "float64"], + "float": ["float32", "float64"], + "str": ["string"], + "unicode": ["string"], + "long": ["int64", "uint64"] + } + primitive_types = [bool, int, long, float] + python2 = True + list_types = [list, tuple] ros_time_types = ["time", "duration"] ros_primitive_types = ["bool", "byte", "char", "int8", "uint8", "int16", @@ -78,9 +95,9 @@ def get_encoder(): elif binary_encoder_type == 'default' or binary_encoder_type == 'b64': binary_encoder = standard_b64encode else: - print "Unknown encoder type '%s'"%binary_encoder_type + print("Unknown encoder type '%s'"%binary_encoder_type) exit(0) - return binary_encoder + return binary_encoder class InvalidMessageException(Exception): def __init__(self, inst): @@ -117,7 +134,8 @@ def _from_inst(inst, rostype): # Special case for uint8[], we encode the string for binary_type, expression in ros_binary_types_list_braces: if expression.sub(binary_type, rostype) in ros_binary_types: - return get_encoder()(inst) + encoded = get_encoder()(inst) + return encoded if python2 else encoded.decode('ascii') # Check for time or duration if rostype in ros_time_types: @@ -193,11 +211,11 @@ def _to_binary_inst(msg): if type(msg) in string_types: try: return standard_b64decode(msg) - except: + except : return msg else: try: - return str(bytearray(msg)) + return bytes(bytearray(msg)) except: return msg @@ -232,7 +250,7 @@ def _to_primitive_inst(msg, rostype, roottype, stack): if msgtype in primitive_types and rostype in type_map[msgtype.__name__]: return msg elif msgtype in string_types and rostype in type_map[msgtype.__name__]: - return msg.encode("utf-8", "ignore") + return msg.encode("utf-8", "ignore") if python2 else msg raise FieldTypeMismatchException(roottype, stack, rostype, msgtype) diff --git a/rosbridge_library/src/rosbridge_library/internal/pngcompression.py b/rosbridge_library/src/rosbridge_library/internal/pngcompression.py index ff63442b7..538348fd5 100644 --- a/rosbridge_library/src/rosbridge_library/internal/pngcompression.py +++ b/rosbridge_library/src/rosbridge_library/internal/pngcompression.py @@ -32,7 +32,7 @@ from PIL import Image from base64 import standard_b64encode, standard_b64decode -from StringIO import StringIO +from io import StringIO from math import floor, ceil, sqrt diff --git a/rosbridge_library/src/rosbridge_library/internal/publishers.py b/rosbridge_library/src/rosbridge_library/internal/publishers.py index 5fbb122e3..7049ba5fc 100644 --- a/rosbridge_library/src/rosbridge_library/internal/publishers.py +++ b/rosbridge_library/src/rosbridge_library/internal/publishers.py @@ -311,7 +311,7 @@ def unregister(self, client_id, topic): return self._publishers[topic].unregister_client(client_id) - if self.unregister_timers.has_key(topic): + if topic in self.unregister_timers: self.unregister_timers[topic].cancel() del self.unregister_timers[topic] self.unregister_timers[topic] = Timer(UNREGISTER_TIMEOUT, self._unregister_impl, diff --git a/rosbridge_library/src/rosbridge_library/internal/ros_loader.py b/rosbridge_library/src/rosbridge_library/internal/ros_loader.py index 25ffc3b83..d1f4c7f7b 100644 --- a/rosbridge_library/src/rosbridge_library/internal/ros_loader.py +++ b/rosbridge_library/src/rosbridge_library/internal/ros_loader.py @@ -61,7 +61,7 @@ class InvalidPackageException(Exception): def __init__(self, package, original_exception): Exception.__init__(self, "Unable to load the manifest for package %s. Caused by: %s" - % (package, original_exception.message) + % (package, str(original_exception)) ) diff --git a/rosbridge_library/src/rosbridge_library/protocol.py b/rosbridge_library/src/rosbridge_library/protocol.py index 47a334963..9abe72ff9 100644 --- a/rosbridge_library/src/rosbridge_library/protocol.py +++ b/rosbridge_library/src/rosbridge_library/protocol.py @@ -52,7 +52,7 @@ def has_binary(d): if type(d)==bson.Binary: return True if type(d)==dict: - for k,v in d.iteritems(): + for k,v in d.items(): if has_binary(v): return True return False @@ -124,7 +124,7 @@ def incoming(self, message_string=""): # if loading whole object fails try to load part of it (from first opening bracket "{" to next closing bracket "}" # .. this causes Exceptions on "inner" closing brackets --> so I suppressed logging of deserialization errors - except Exception, e: + except Exception as e: if self.bson_only_mode: # Since BSON should be used in conjunction with a network handler # that receives exactly one full BSON message. @@ -157,7 +157,7 @@ def incoming(self, message_string=""): self.buffer = self.buffer[end+1:len(self.buffer)] # jump out of inner loop if json-decode succeeded break - except Exception,e: + except Exception as e: # debug json-decode errors with this line #print e pass @@ -177,11 +177,11 @@ def incoming(self, message_string=""): if "receiver" in msg: self.log("error", "Received a rosbridge v1.0 message. Please refer to rosbridge.org for the correct format of rosbridge v2.0 messages. Original message was: %s" % message_string) else: - self.log("error", "Received a message without an op. All messages require 'op' field with value one of: %s. Original message was: %s" % (self.operations.keys(), message_string), mid) + self.log("error", "Received a message without an op. All messages require 'op' field with value one of: %s. Original message was: %s" % (list(self.operations.keys()), message_string), mid) return op = msg["op"] if op not in self.operations: - self.log("error", "Unknown operation: %s. Allowed operations: %s" % (op, self.operations.keys()), mid) + self.log("error", "Unknown operation: %s. Allowed operations: %s" % (op, list(self.operations.keys())), mid) return # this way a client can change/overwrite it's active values anytime by just including parameter field in any message sent to rosbridge # maybe need to be improved to bind parameter values to specific operation.. @@ -312,7 +312,7 @@ def deserialize(self, msg, cid=None): return bson_message.decode() else: return json.loads(msg) - except Exception, e: + except Exception as e: # if we did try to deserialize whole buffer .. first try to let self.incoming check for multiple/partial json-decodes before logging error # .. this means, if buffer is not == msg --> we tried to decode part of buffer diff --git a/rosbridge_library/src/rosbridge_library/rosbridge_protocol.py b/rosbridge_library/src/rosbridge_library/rosbridge_protocol.py index 479b98f1d..7900c7bac 100644 --- a/rosbridge_library/src/rosbridge_library/rosbridge_protocol.py +++ b/rosbridge_library/src/rosbridge_library/rosbridge_protocol.py @@ -30,6 +30,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from __future__ import print_function from rosbridge_library.protocol import Protocol from rosbridge_library.capabilities.call_service import CallService from rosbridge_library.capabilities.advertise import Advertise @@ -48,9 +49,9 @@ class RosbridgeProtocol(Protocol): """ Adds the handlers for the rosbridge opcodes """ rosbridge_capabilities = [CallService, Advertise, Publish, Subscribe, Defragment, AdvertiseService, ServiceResponse, UnadvertiseService] - print "registered capabilities (classes):" + print("registered capabilities (classes):") for cap in rosbridge_capabilities: - print " -", str(cap) + print(" -", str(cap)) parameters = None diff --git a/rosbridge_library/src/rosbridge_library/util/__init__.py b/rosbridge_library/src/rosbridge_library/util/__init__.py index 872311169..885f8a515 100644 --- a/rosbridge_library/src/rosbridge_library/util/__init__.py +++ b/rosbridge_library/src/rosbridge_library/util/__init__.py @@ -6,3 +6,10 @@ import simplejson as json except ImportError: import json + +# Differing string types for Python 2 and 3 +import sys +if sys.version_info >= (3, 0): + string_types = (str,) +else: + string_types = (str, unicode) diff --git a/rosbridge_library/test/capabilities/test_subscribe.py b/rosbridge_library/test/capabilities/test_subscribe.py index c181a3c92..00769fe9c 100755 --- a/rosbridge_library/test/capabilities/test_subscribe.py +++ b/rosbridge_library/test/capabilities/test_subscribe.py @@ -49,7 +49,7 @@ def test_update_params(self): self.assertEqual(subscription.fragment_size, min_frag_size) self.assertEqual(subscription.compression, "none") - subscription.clients.values()[0]["compression"] = "png" + list(subscription.clients.values())[0]["compression"] = "png" subscription.update_params() diff --git a/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_client_complex-srv.py b/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_client_complex-srv.py index 2749c989b..352e911bb 100755 --- a/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_client_complex-srv.py +++ b/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_client_complex-srv.py @@ -1,4 +1,5 @@ #!/usr/bin/python +from __future__ import print_function import socket from rosbridge_library.util import json @@ -33,7 +34,7 @@ def request_service(): #"count" : request_byte_count # count is the parameter for send_bytes as defined in srv-file (always put into args field!) } service_request = json.dumps(service_request_object) - print "sending JSON-message to rosbridge:", service_request + print("sending JSON-message to rosbridge:", service_request) sock.send(service_request) ################################################################################ @@ -60,7 +61,7 @@ def request_service(): if buffer == "": buffer = incoming if incoming == "": - print "closing socket" + print("closing socket") sock.close() break else: @@ -71,7 +72,7 @@ def request_service(): if data_object["op"] == "service_response": reconstructed = buffer done = True - except Exception, e: + except Exception as e: #print "direct access to JSON failed.." #print e pass @@ -86,13 +87,13 @@ def request_service(): fragment = fragment + "}" try: result.append(json.loads(fragment)) # try to parse json from string, and append if successful - except Exception, e: + except Exception as e: #print e #print result_string raise # re-raise the last exception, allows to see and continue with processing of exception fragment_count = len(result) - print "fragment_count:", fragment_count + print("fragment_count:", fragment_count) announced = int(result[0]["total"]) if fragment_count == announced: # if all fragments received --> sort and defragment # sort fragments @@ -105,23 +106,23 @@ def request_service(): for fragment in sorted_result: reconstructed = reconstructed + fragment["data"] done = True - except Exception, e: + except Exception as e: #print e pass - except Exception, e: + except Exception as e: # print e pass returned_data = json.loads(reconstructed) # when service response is received --> access it (as defined in srv-file) if returned_data["values"] == None: - print "response was None -> service was not available" + print("response was None -> service was not available") else: - print "received:" - print returned_data#["values"]#["data"].decode('base64','strict') # decode values-field + print("received:") + print(returned_data)#["values"]#["data"].decode('base64','strict') # decode values-field -except Exception, e: - print "ERROR - could not receive service_response" - print e +except Exception as e: + print("ERROR - could not receive service_response") + print(e) sock.close() # close socket diff --git a/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_server_complex-srv.py b/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_server_complex-srv.py index 37b66f334..36cebe775 100755 --- a/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_server_complex-srv.py +++ b/rosbridge_library/test/experimental/complex_srv+tcp/test_non-ros_service_server_complex-srv.py @@ -1,4 +1,5 @@ #!/usr/bin/python +from __future__ import print_function import sys import socket import time @@ -103,7 +104,7 @@ def wait_for_service_request(): while not done: incoming = tcp_socket.recv(max_msg_length) # get data from socket if incoming == '': - print "connection closed by peer" + print("connection closed by peer") sys.exit(1) buffer = buffer + incoming # append data to buffer try: # try to parse JSON from buffer @@ -112,7 +113,7 @@ def wait_for_service_request(): data = buffer done = True return data # if parsing was successful --> return data string - except Exception, e: + except Exception as e: #print "direct_access error:" #print e pass @@ -146,17 +147,17 @@ def wait_for_service_request(): #print "reconstructed", reconstructed buffer = "" # empty buffer done = True - print "reconstructed message from", len(result), "fragments" + print("reconstructed message from", len(result), "fragments") #print reconstructed return reconstructed - except Exception, e: - print "not possible to defragment:", buffer - print e - except Exception, e: - print "defrag_error:", buffer - print e + except Exception as e: + print("not possible to defragment:", buffer) + print(e) + except Exception as e: + print("defrag_error:", buffer) + print(e) pass - except Exception, e: + except Exception as e: #print "network-error(?):", e pass return data @@ -203,7 +204,7 @@ def list_of_fragments(full_message, fragment_size): tcp_socket = connect_tcp_socket() # open tcp_socket advertise_service() # advertise service in ROS (via rosbridge) -print "service provider started and waiting for requests" +print("service provider started and waiting for requests") try: # allows to catch KeyboardInterrupt while True: # loop forever (or until ctrl-c is pressed) @@ -215,21 +216,21 @@ def list_of_fragments(full_message, fragment_size): elif data != None and len(data) > 0: # received service_request (or at least some data..) response = calculate_service_response(data) # generate service_response - print "response calculated, now splitting into fragments.." + print("response calculated, now splitting into fragments..") fragment_list = list_of_fragments(response, send_fragment_size) # generate fragments to send to rosbridge - print "sending", len(fragment_list), "messages as response" + print("sending", len(fragment_list), "messages as response") for fragment in fragment_list: #print "sending:" ,fragment send_service_response(fragment) # send service_response to rosbridge (or fragments; just send any list entry) time.sleep(send_fragment_delay) # (not needed if using patched rosbridge protocol.py) - except Exception, e: - print e + except Exception as e: + print(e) pass except KeyboardInterrupt: try: unadvertise_service() # unadvertise service tcp_socket.close() # close tcp_socket - except Exception, e: - print e - print "non-ros_service_server stopped because user pressed \"Ctrl-C\"" + except Exception as e: + print(e) + print("non-ros_service_server stopped because user pressed \"Ctrl-C\"") diff --git a/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_client_fragmented.py b/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_client_fragmented.py index ee31bf3fa..6a02bcb4e 100755 --- a/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_client_fragmented.py +++ b/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_client_fragmented.py @@ -1,4 +1,5 @@ #!/usr/bin/python +from __future__ import print_function import socket from rosbridge_library.util import json @@ -33,7 +34,7 @@ def request_service(): } } service_request = json.dumps(service_request_object) - print "sending JSON-message to rosbridge:", service_request + print("sending JSON-message to rosbridge:", service_request) sock.send(service_request) ################################################################################ @@ -60,7 +61,7 @@ def request_service(): if buffer == "": buffer = incoming if incoming == "": - print "closing socket" + print("closing socket") sock.close() break else: @@ -71,7 +72,7 @@ def request_service(): if data_object["op"] == "service_response": reconstructed = buffer done = True - except Exception, e: + except Exception as e: #print "direct access to JSON failed.." #print e pass @@ -86,13 +87,13 @@ def request_service(): fragment = fragment + "}" try: result.append(json.loads(fragment)) # try to parse json from string, and append if successful - except Exception, e: + except Exception as e: #print e #print result_string raise # re-raise the last exception, allows to see and continue with processing of exception fragment_count = len(result) - print "fragment_count:", fragment_count + print("fragment_count:", fragment_count) announced = int(result[0]["total"]) if fragment_count == announced: # if all fragments received --> sort and defragment # sort fragments @@ -105,23 +106,23 @@ def request_service(): for fragment in sorted_result: reconstructed = reconstructed + fragment["data"] done = True - except Exception, e: + except Exception as e: #print e pass - except Exception, e: + except Exception as e: # print e pass returned_data = json.loads(reconstructed) # when service response is received --> access it (as defined in srv-file) if returned_data["values"] == None: - print "response was None -> service was not available" + print("response was None -> service was not available") else: - print "received:" - print returned_data["values"]["data"].decode('base64','strict') # decode values-field + print("received:") + print(returned_data["values"]["data"].decode('base64','strict')) # decode values-field -except Exception, e: - print "ERROR - could not receive service_response" - print e +except Exception as e: + print("ERROR - could not receive service_response") + print(e) sock.close() # close socket diff --git a/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_server_fragmented.py b/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_server_fragmented.py index 77d06beaf..1d0679f07 100755 --- a/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_server_fragmented.py +++ b/rosbridge_library/test/experimental/fragmentation+srv+tcp/test_non-ros_service_server_fragmented.py @@ -1,4 +1,5 @@ #!/usr/bin/python +from __future__ import print_function import sys import socket import time @@ -43,7 +44,7 @@ def calculate_service_response(request): #message += str(chr(randint(32,126))) message+= str(chr(randint(32,126))) if i% 100000 == 0: - print count - i, "bytes left to generate" + print(count - i, "bytes left to generate") """ IMPORTANT! @@ -103,7 +104,7 @@ def wait_for_service_request(): while not done: incoming = tcp_socket.recv(max_msg_length) # get data from socket if incoming == '': - print "connection closed by peer" + print("connection closed by peer") sys.exit(1) buffer = buffer + incoming # append data to buffer try: # try to parse JSON from buffer @@ -112,7 +113,7 @@ def wait_for_service_request(): data = buffer done = True return data # if parsing was successful --> return data string - except Exception, e: + except Exception as e: #print "direct_access error:" #print e pass @@ -146,17 +147,17 @@ def wait_for_service_request(): #print "reconstructed", reconstructed buffer = "" # empty buffer done = True - print "reconstructed message from", len(result), "fragments" + print("reconstructed message from", len(result), "fragments") #print reconstructed return reconstructed - except Exception, e: - print "not possible to defragment:", buffer - print e - except Exception, e: - print "defrag_error:", buffer - print e + except Exception as e: + print("not possible to defragment:", buffer) + print(e) + except Exception as e: + print("defrag_error:", buffer) + print(e) pass - except Exception, e: + except Exception as e: #print "network-error(?):", e pass return data @@ -203,7 +204,7 @@ def list_of_fragments(full_message, fragment_size): tcp_socket = connect_tcp_socket() # open tcp_socket advertise_service() # advertise service in ROS (via rosbridge) -print "service provider started and waiting for requests" +print("service provider started and waiting for requests") try: # allows to catch KeyboardInterrupt while True: # loop forever (or until ctrl-c is pressed) @@ -215,21 +216,21 @@ def list_of_fragments(full_message, fragment_size): elif data != None and len(data) > 0: # received service_request (or at least some data..) response = calculate_service_response(data) # generate service_response - print "response calculated, now splitting into fragments.." + print("response calculated, now splitting into fragments..") fragment_list = list_of_fragments(response, send_fragment_size) # generate fragments to send to rosbridge - print "sending", len(fragment_list), "messages as response" + print("sending", len(fragment_list), "messages as response") for fragment in fragment_list: #print "sending:" ,fragment send_service_response(fragment) # send service_response to rosbridge (or fragments; just send any list entry) time.sleep(send_fragment_delay) # (not needed if using patched rosbridge protocol.py) - except Exception, e: - print e + except Exception as e: + print(e) pass except KeyboardInterrupt: try: unadvertise_service() # unadvertise service tcp_socket.close() # close tcp_socket - except Exception, e: - print e - print "non-ros_service_server stopped because user pressed \"Ctrl-C\"" + except Exception as e: + print(e) + print("non-ros_service_server stopped because user pressed \"Ctrl-C\"") diff --git a/rosbridge_library/test/internal/publishers/test_publisher_consistency_listener.py b/rosbridge_library/test/internal/publishers/test_publisher_consistency_listener.py index 9c5eb94cb..4bffb15a7 100755 --- a/rosbridge_library/test/internal/publishers/test_publisher_consistency_listener.py +++ b/rosbridge_library/test/internal/publishers/test_publisher_consistency_listener.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +from __future__ import print_function import sys import rospy import rostest @@ -96,14 +97,14 @@ def test_immediate_publish(self): received = {"msg": None} def callback(msg): - print "Received a msg! ", msg + print("Received a msg! ", msg) received["msg"] = msg rospy.Subscriber(topic, msg_class, callback) class temp_listener(rospy.SubscribeListener): def peer_subscribe(self, topic_name, topic_publish, peer_publish): - print "peer subscribe in temp listener" + print("peer subscribe in temp listener") listener = PublisherConsistencyListener() publisher = rospy.Publisher(topic, msg_class, temp_listener()) diff --git a/rosbridge_library/test/internal/subscribers/test_multi_subscriber.py b/rosbridge_library/test/internal/subscribers/test_multi_subscriber.py index 762625236..8b52311a1 100755 --- a/rosbridge_library/test/internal/subscribers/test_multi_subscriber.py +++ b/rosbridge_library/test/internal/subscribers/test_multi_subscriber.py @@ -91,7 +91,7 @@ def test_subscribe_receive_json(self): multi = MultiSubscriber(topic, msg_type) received = {"msg": None} - + def cb(msg): received["msg"] = msg @@ -106,7 +106,7 @@ def test_subscribe_receive_json_multiple(self): msg_type = "std_msgs/Int32" client = "client_test_subscribe_receive_json_multiple" - numbers = range(100) + numbers = list(range(100)) pub = rospy.Publisher(topic, Int32) multi = MultiSubscriber(topic, msg_type) diff --git a/rosbridge_library/test/internal/subscribers/test_subscription_modifiers.py b/rosbridge_library/test/internal/subscribers/test_subscription_modifiers.py index 7fe8d8bf4..9a1b72d83 100755 --- a/rosbridge_library/test/internal/subscribers/test_subscription_modifiers.py +++ b/rosbridge_library/test/internal/subscribers/test_subscription_modifiers.py @@ -64,7 +64,7 @@ def cb(msg): # no messages will be handled in the next 10 seconds # these will fill up the queue, with newer values displacing old ones - # nothing gets sent because the throttle rate + # nothing gets sent because the throttle rate for x in msgs: handler.handle_message(x) @@ -73,7 +73,7 @@ def cb(msg): time.sleep(0.1) try: - self.assertEqual(["hello"] + range(990, 1000), received["msgs"]) + self.assertEqual(["hello"] + list(range(990, 1000)), received["msgs"]) except: handler.finish() raise @@ -113,7 +113,7 @@ def cb(msg): def cb(msg): received["msgs"].append(msg) handler.publish = cb - xs = range(10000) + xs = list(range(10000)) for x in xs: handler.handle_message(x) @@ -124,22 +124,22 @@ def help_test_throttle(self, handler, throttle_rate): handler = handler.set_queue_length(0) handler = handler.set_throttle_rate(throttle_rate) self.assertIsInstance(handler, subscribe.ThrottleMessageHandler) - + msg = "test_throttle_message_handler" - + # First, try with a single message received = {"msg": None} - + def cb(msg): received["msg"] = msg - + handler.publish = cb # ensure the handler doesn't swallow this message time.sleep(2.0 * handler.throttle_rate) handler.handle_message(msg) self.assertEqual(received["msg"], msg) - + # sleep to make sure the handler sends right away for the second part time.sleep(2.0 * handler.throttle_rate) @@ -166,7 +166,7 @@ def cb(msg): def help_test_queue(self, handler, queue_length): handler = handler.set_queue_length(queue_length) self.assertIsInstance(handler, subscribe.QueueMessageHandler) - + received = {"msgs": []} def cb(msg): @@ -174,7 +174,7 @@ def cb(msg): handler.publish = cb - msgs = range(queue_length) + msgs = list(range(queue_length)) for x in msgs: handler.handle_message(x) @@ -196,7 +196,7 @@ def cb(msg): handler.publish = cb throttle_rate_sec = throttle_rate / 1000.0 - + # ensure previous tests' last sent time is long enough ago time.sleep(throttle_rate_sec) for x in range(queue_length): diff --git a/rosbridge_library/test/internal/test_compression.py b/rosbridge_library/test/internal/test_compression.py index 0218ee189..de3a284f0 100755 --- a/rosbridge_library/test/internal/test_compression.py +++ b/rosbridge_library/test/internal/test_compression.py @@ -13,13 +13,13 @@ def setUp(self): rospy.init_node("test_compression") def test_compress(self): - bytes = range(128) * 10000 + bytes = list(range(128)) * 10000 string = str(bytearray(bytes)) encoded = pngcompression.encode(string) self.assertNotEqual(string, encoded) def test_compress_decompress(self): - bytes = range(128) * 10000 + bytes = list(range(128)) * 10000 string = str(bytearray(bytes)) encoded = pngcompression.encode(string) self.assertNotEqual(string, encoded) diff --git a/rosbridge_library/test/internal/test_message_conversion.py b/rosbridge_library/test/internal/test_message_conversion.py index 5374afcff..01c2d1571 100755 --- a/rosbridge_library/test/internal/test_message_conversion.py +++ b/rosbridge_library/test/internal/test_message_conversion.py @@ -1,16 +1,25 @@ #!/usr/bin/env python +from __future__ import print_function import sys import rospy import rostest import unittest from json import loads, dumps -from StringIO import StringIO +try: + from cStringIO import StringIO # Python 2.x +except ImportError: + from io import BytesIO as StringIO # Python 3.x from rosbridge_library.internal import message_conversion as c from rosbridge_library.internal import ros_loader from base64 import standard_b64encode, standard_b64decode +if sys.version_info >= (3, 0): + string_types = (str,) +else: + string_types = (str, unicode) + class TestMessageConversion(unittest.TestCase): @@ -29,7 +38,7 @@ def validate_instance(self, inst1): inst2._check_types() def msgs_equal(self, msg1, msg2): - if type(msg1) in [str, unicode] and type(msg2) in [str, unicode]: + if type(msg1) in string_types and type(msg2) in string_types: pass else: self.assertEqual(type(msg1), type(msg2)) @@ -189,7 +198,7 @@ def test_time_msg_now(self): currenttime = rospy.get_rostime() self.validate_instance(inst) extracted = c.extract_values(inst) - print extracted + print(extracted) self.assertIn("data", extracted) self.assertIn("secs", extracted["data"]) self.assertIn("nsecs", extracted["data"]) @@ -244,26 +253,26 @@ def test_int8_msg(rostype, data): for msgtype in ["TestChar", "TestUInt8"]: rostype = "rosbridge_library/" + msgtype - int8s = range(0, 256) + int8s = list(range(0, 256)) ret = test_int8_msg(rostype, int8s) - self.assertEqual(ret, str(bytearray(int8s))) + self.assertEqual(ret, bytes(bytearray(int8s))) - str_int8s = str(bytearray(int8s)) + str_int8s = bytes(bytearray(int8s)) - b64str_int8s = standard_b64encode(str_int8s) + b64str_int8s = standard_b64encode(str_int8s).decode('ascii') ret = test_int8_msg(rostype, b64str_int8s) self.assertEqual(ret, str_int8s) for msgtype in ["TestUInt8FixedSizeArray16"]: rostype = "rosbridge_library/" + msgtype - int8s = range(0, 16) + int8s = list(range(0, 16)) ret = test_int8_msg(rostype, int8s) - self.assertEqual(ret, str(bytearray(int8s))) + self.assertEqual(ret, bytes(bytearray(int8s))) - str_int8s = str(bytearray(int8s)) + str_int8s = bytes(bytearray(int8s)) - b64str_int8s = standard_b64encode(str_int8s) + b64str_int8s = standard_b64encode(str_int8s).decode('ascii') ret = test_int8_msg(rostype, b64str_int8s) self.assertEqual(ret, str_int8s) diff --git a/rosbridge_library/test/internal/test_services.py b/rosbridge_library/test/internal/test_services.py index 0b2282ede..87a9118a8 100755 --- a/rosbridge_library/test/internal/test_services.py +++ b/rosbridge_library/test/internal/test_services.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +from __future__ import print_function import sys import rospy import rostest @@ -12,6 +13,11 @@ from roscpp.srv import GetLoggers +if sys.version_info >= (3, 0): + string_types = (str,) +else: + string_types = (str, unicode) + def populate_random_args(d): # Given a dictionary d, replaces primitives with random values @@ -21,7 +27,7 @@ def populate_random_args(d): return d elif isinstance(d, str): return str(random.random()) - elif isinstance(d, unicode): + elif sys.version_info < (3,0) and isinstance(d, unicode): return unicode(random.random()) elif isinstance(d, bool): return True @@ -56,10 +62,10 @@ def callback(self, req): try: rsp = c.populate_instance(gen, rsp) except: - print "populating instance" - print rsp - print "populating with" - print gen + print("populating instance") + print(rsp) + print("populating with") + print(gen) raise self.output = gen return rsp @@ -72,8 +78,8 @@ def error(self, exc): def validate(self, equality_function): if hasattr(self, "exc"): - print self.exc - print self.exc.message + print(self.exc) + print(self.exc.message) raise self.exc equality_function(self.input, c.extract_values(self.req)) equality_function(self.output, self.rsp) @@ -85,7 +91,7 @@ def setUp(self): rospy.init_node("test_services") def msgs_equal(self, msg1, msg2): - if type(msg1) in [str, unicode] and type(msg2) in [str, unicode]: + if type(msg1) in string_types and type(msg2) in string_types: pass else: self.assertEqual(type(msg1), type(msg2)) diff --git a/rosbridge_server/scripts/rosbridge_tcp.py b/rosbridge_server/scripts/rosbridge_tcp.py index aaa645572..052941b4d 100755 --- a/rosbridge_server/scripts/rosbridge_tcp.py +++ b/rosbridge_server/scripts/rosbridge_tcp.py @@ -1,5 +1,6 @@ #!/usr/bin/env python +from __future__ import print_function from rospy import init_node, get_param, loginfo, logerr, on_shutdown from rosbridge_server import RosbridgeTcpSocket @@ -13,7 +14,11 @@ from functools import partial from signal import signal, SIGINT, SIG_DFL -import SocketServer +try: + import SocketServer +except ImportError: + import socketserver as SocketServer + import sys import time @@ -30,9 +35,9 @@ def shutdown_hook(server): retry_count = 0 while not loaded: retry_count += 1 - print "trying to start rosbridge TCP server.." + print("trying to start rosbridge TCP server..") try: - print "" + print("") init_node("rosbridge_tcp") signal(SIGINT, SIG_DFL) @@ -74,7 +79,7 @@ def shutdown_hook(server): element.strip().strip("'") for element in get_param('~params_glob', '')[1:-1].split(',') if len(element.strip().strip("'")) > 0] - + # update parameters if provided via commandline # .. could implemented 'better' (value/type checking, etc.. ) if "--port" in sys.argv: @@ -82,7 +87,7 @@ def shutdown_hook(server): if idx < len(sys.argv): port = int(sys.argv[idx]) else: - print "--port argument provided without a value." + print("--port argument provided without a value.") sys.exit(-1) if "--host" in sys.argv: @@ -90,7 +95,7 @@ def shutdown_hook(server): if idx < len(sys.argv): host = str(sys.argv[idx]) else: - print "--host argument provided without a value." + print("--host argument provided without a value.") sys.exit(-1) if "--incoming_buffer" in sys.argv: @@ -98,7 +103,7 @@ def shutdown_hook(server): if idx < len(sys.argv): incoming_buffer = int(sys.argv[idx]) else: - print "--incoming_buffer argument provided without a value." + print("--incoming_buffer argument provided without a value.") sys.exit(-1) if "--socket_timeout" in sys.argv: @@ -106,7 +111,7 @@ def shutdown_hook(server): if idx < len(sys.argv): socket_timeout = int(sys.argv[idx]) else: - print "--socket_timeout argument provided without a value." + print("--socket_timeout argument provided without a value.") sys.exit(-1) if "--retry_startup_delay" in sys.argv: @@ -114,7 +119,7 @@ def shutdown_hook(server): if idx < len(sys.argv): retry_startup_delay = int(sys.argv[idx]) else: - print "--retry_startup_delay argument provided without a value." + print("--retry_startup_delay argument provided without a value.") sys.exit(-1) if "--fragment_timeout" in sys.argv: @@ -122,7 +127,7 @@ def shutdown_hook(server): if idx < len(sys.argv): fragment_timeout = int(sys.argv[idx]) else: - print "--fragment_timeout argument provided without a value." + print("--fragment_timeout argument provided without a value.") sys.exit(-1) if "--delay_between_messages" in sys.argv: @@ -130,7 +135,7 @@ def shutdown_hook(server): if idx < len(sys.argv): delay_between_messages = float(sys.argv[idx]) else: - print "--delay_between_messages argument provided without a value." + print("--delay_between_messages argument provided without a value.") sys.exit(-1) if "--max_message_size" in sys.argv: @@ -142,7 +147,7 @@ def shutdown_hook(server): else: max_message_size = int(value) else: - print "--max_message_size argument provided without a value. (can be None or )" + print("--max_message_size argument provided without a value. (can be None or )") sys.exit(-1) # export parameters to handler class @@ -163,7 +168,7 @@ def shutdown_hook(server): else: RosbridgeTcpSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--topics_glob argument provided without a value. (can be None or a list)" + print("--topics_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--services_glob" in sys.argv: @@ -175,7 +180,7 @@ def shutdown_hook(server): else: RosbridgeTcpSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--services_glob argument provided without a value. (can be None or a list)" + print("--services_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--params_glob" in sys.argv: @@ -187,7 +192,7 @@ def shutdown_hook(server): else: RosbridgeTcpSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--params_glob argument provided without a value. (can be None or a list)" + print("--params_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--bson_only_mode" in sys.argv: @@ -219,6 +224,6 @@ def shutdown_hook(server): server.serve_forever() loaded = True - except Exception, e: + except Exception as e: time.sleep(retry_startup_delay) - print "server loaded" + print("server loaded") diff --git a/rosbridge_server/scripts/rosbridge_udp.py b/rosbridge_server/scripts/rosbridge_udp.py index 7bcf67189..52fc2085e 100755 --- a/rosbridge_server/scripts/rosbridge_udp.py +++ b/rosbridge_server/scripts/rosbridge_udp.py @@ -31,6 +31,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from __future__ import print_function import rospy import sys @@ -89,7 +90,7 @@ def shutdown_hook(): if idx < len(sys.argv): port = int(sys.argv[idx]) else: - print "--port argument provided without a value." + print("--port argument provided without a value.") sys.exit(-1) if "--interface" in sys.argv: @@ -97,7 +98,7 @@ def shutdown_hook(): if idx < len(sys.argv): interface = int(sys.argv[idx]) else: - print "--interface argument provided without a value." + print("--interface argument provided without a value.") sys.exit(-1) if "--fragment_timeout" in sys.argv: @@ -105,7 +106,7 @@ def shutdown_hook(): if idx < len(sys.argv): RosbridgeUdpSocket.fragment_timeout = int(sys.argv[idx]) else: - print "--fragment_timeout argument provided without a value." + print("--fragment_timeout argument provided without a value.") sys.exit(-1) if "--delay_between_messages" in sys.argv: @@ -113,7 +114,7 @@ def shutdown_hook(): if idx < len(sys.argv): RosbridgeUdpSocket.delay_between_messages = float(sys.argv[idx]) else: - print "--delay_between_messages argument provided without a value." + print("--delay_between_messages argument provided without a value.") sys.exit(-1) if "--max_message_size" in sys.argv: @@ -125,7 +126,7 @@ def shutdown_hook(): else: RosbridgeUdpSocket.max_message_size = int(value) else: - print "--max_message_size argument provided without a value. (can be None or )" + print("--max_message_size argument provided without a value. (can be None or )") sys.exit(-1) if "--topics_glob" in sys.argv: @@ -137,7 +138,7 @@ def shutdown_hook(): else: RosbridgeUdpSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--topics_glob argument provided without a value. (can be None or a list)" + print("--topics_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--services_glob" in sys.argv: @@ -149,7 +150,7 @@ def shutdown_hook(): else: RosbridgeUdpSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--services_glob argument provided without a value. (can be None or a list)" + print("--services_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--params_glob" in sys.argv: @@ -161,7 +162,7 @@ def shutdown_hook(): else: RosbridgeUdpSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--params_glob argument provided without a value. (can be None or a list)" + print("--params_glob argument provided without a value. (can be None or a list)") sys.exit(-1) # To be able to access the list of topics and services, you must be able to access the rosapi services. diff --git a/rosbridge_server/scripts/rosbridge_websocket.py b/rosbridge_server/scripts/rosbridge_websocket.py index d48b27da5..1647a4af3 100755 --- a/rosbridge_server/scripts/rosbridge_websocket.py +++ b/rosbridge_server/scripts/rosbridge_websocket.py @@ -31,6 +31,7 @@ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. +from __future__ import print_function import rospy import sys @@ -100,7 +101,7 @@ def shutdown_hook(): if idx < len(sys.argv): port = int(sys.argv[idx]) else: - print "--port argument provided without a value." + print("--port argument provided without a value.") sys.exit(-1) if "--address" in sys.argv: @@ -108,7 +109,7 @@ def shutdown_hook(): if idx < len(sys.argv): address = int(sys.argv[idx]) else: - print "--address argument provided without a value." + print("--address argument provided without a value.") sys.exit(-1) if "--retry_startup_delay" in sys.argv: @@ -116,7 +117,7 @@ def shutdown_hook(): if idx < len(sys.argv): retry_startup_delay = int(sys.argv[idx]) else: - print "--retry_startup_delay argument provided without a value." + print("--retry_startup_delay argument provided without a value.") sys.exit(-1) if "--fragment_timeout" in sys.argv: @@ -124,7 +125,7 @@ def shutdown_hook(): if idx < len(sys.argv): RosbridgeWebSocket.fragment_timeout = int(sys.argv[idx]) else: - print "--fragment_timeout argument provided without a value." + print("--fragment_timeout argument provided without a value.") sys.exit(-1) if "--delay_between_messages" in sys.argv: @@ -132,7 +133,7 @@ def shutdown_hook(): if idx < len(sys.argv): RosbridgeWebSocket.delay_between_messages = float(sys.argv[idx]) else: - print "--delay_between_messages argument provided without a value." + print("--delay_between_messages argument provided without a value.") sys.exit(-1) if "--max_message_size" in sys.argv: @@ -144,7 +145,7 @@ def shutdown_hook(): else: RosbridgeWebSocket.max_message_size = int(value) else: - print "--max_message_size argument provided without a value. (can be None or )" + print("--max_message_size argument provided without a value. (can be None or )") sys.exit(-1) if "--topics_glob" in sys.argv: @@ -156,7 +157,7 @@ def shutdown_hook(): else: RosbridgeWebSocket.topics_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--topics_glob argument provided without a value. (can be None or a list)" + print("--topics_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--services_glob" in sys.argv: @@ -168,7 +169,7 @@ def shutdown_hook(): else: RosbridgeWebSocket.services_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--services_glob argument provided without a value. (can be None or a list)" + print("--services_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if "--params_glob" in sys.argv: @@ -180,11 +181,11 @@ def shutdown_hook(): else: RosbridgeWebSocket.params_glob = [element.strip().strip("'") for element in value[1:-1].split(',')] else: - print "--params_glob argument provided without a value. (can be None or a list)" + print("--params_glob argument provided without a value. (can be None or a list)") sys.exit(-1) if ("--bson_only_mode" in sys.argv) or bson_only_mode: - print "bson_only_mode is only supported in the TCP Version of Rosbridge currently. Ignoring bson_only_mode argument..." + print("bson_only_mode is only supported in the TCP Version of Rosbridge currently. Ignoring bson_only_mode argument...") # To be able to access the list of topics and services, you must be able to access the rosapi services. if RosbridgeWebSocket.services_glob: diff --git a/rosbridge_server/src/rosbridge_server/__init__.py b/rosbridge_server/src/rosbridge_server/__init__.py index 4ccabd1a8..311eceae8 100644 --- a/rosbridge_server/src/rosbridge_server/__init__.py +++ b/rosbridge_server/src/rosbridge_server/__init__.py @@ -1,3 +1,4 @@ -from websocket_handler import RosbridgeWebSocket -from tcp_handler import RosbridgeTcpSocket -from udp_handler import RosbridgeUdpSocket,RosbridgeUdpFactory +from __future__ import absolute_import +from .websocket_handler import RosbridgeWebSocket +from .tcp_handler import RosbridgeTcpSocket +from .udp_handler import RosbridgeUdpSocket,RosbridgeUdpFactory diff --git a/rosbridge_server/src/rosbridge_server/tcp_handler.py b/rosbridge_server/src/rosbridge_server/tcp_handler.py index 3c9d5b99b..1d747ff4e 100755 --- a/rosbridge_server/src/rosbridge_server/tcp_handler.py +++ b/rosbridge_server/src/rosbridge_server/tcp_handler.py @@ -2,7 +2,10 @@ import struct from rosbridge_library.rosbridge_protocol import RosbridgeProtocol -import SocketServer +try: + import SocketServer +except ImportError: + import socketserver as SocketServer class RosbridgeTcpSocket(SocketServer.BaseRequestHandler): """ @@ -98,7 +101,7 @@ def handle(self): self.protocol.incoming(data.strip('')) else: pass - except Exception, e: + except Exception as e: pass self.protocol.log("debug", "socket connection timed out! (ignore warning if client is only listening..)") diff --git a/rosbridge_server/src/rosbridge_server/udp_handler.py b/rosbridge_server/src/rosbridge_server/udp_handler.py index bc8cb542f..8ae691d5c 100644 --- a/rosbridge_server/src/rosbridge_server/udp_handler.py +++ b/rosbridge_server/src/rosbridge_server/udp_handler.py @@ -8,7 +8,8 @@ class RosbridgeUdpFactory(DatagramProtocol): def startProtocol(self): self.socks = dict() - def datagramReceived(self, message, (host, port)): + def datagramReceived(self, message, source_addr): + (host, port) = source_addr endpoint = host.__str__() + port.__str__() if endpoint in self.socks: self.socks[endpoint].datagramReceived(message)