rospy: starting to reorganize codebase to hide non-user-facing code. Work in progress

This commit is contained in:
Ken Conley 2010-04-28 00:20:16 +00:00
parent 1ea162c92c
commit f753a90fee
33 changed files with 152 additions and 140 deletions

View File

@ -42,7 +42,6 @@ See U{http://ros.org/wiki/rospy}
from roslib.rosenv import ROS_ROOT, ROS_MASTER_URI, ROS_HOSTNAME, ROS_NAMESPACE, ROS_PACKAGE_PATH, ROS_LOG_DIR
import rospy.core
import rospy.init
# import symbols into rospy namespace
# NOTE: there are much better ways to configure python module
@ -69,8 +68,9 @@ from rospy.msproxy import NodeProxy, MasterProxy
from rospy.names import get_name, get_caller_id, get_namespace, resolve_name, remap_name
from rospy.rostime import Time, Duration, get_rostime, get_time
from rospy.service import ServiceException, ServiceDefinition
# - use tcp ros implementation of services
from rospy.tcpros_service import Service, ServiceProxy, wait_for_service
from rospy.impl.tcpros_service import Service, ServiceProxy, wait_for_service
from rospy.topics import Message, SubscribeListener, Publisher, Subscriber
## \defgroup validators Validators

View File

@ -52,11 +52,12 @@ import roslib.network
import rospy.core
from rospy.core import logwarn, loginfo, logerr, logdebug
import rospy.exceptions
import rospy.init
import rospy.names
import rospy.rosout
import rospy.rostime
import rospy.simtime
import rospy.impl.init
import rospy.impl.rosout
import rospy.impl.simtime
TIMEOUT_READY = 15.0 #seconds
@ -67,7 +68,7 @@ WARN = roslib.msg.Log.WARN
ERROR = roslib.msg.Log.ERROR
FATAL = roslib.msg.Log.FATAL
# hide rospy.init implementation from users
# hide rospy.impl.init implementation from users
def get_node_proxy():
"""
Retrieve L{NodeProxy} for slave node running on this machine.
@ -75,7 +76,7 @@ def get_node_proxy():
@return: slave node API handle
@rtype: L{rospy.NodeProxy}
"""
return rospy.init.get_node_proxy()
return rospy.impl.init.get_node_proxy()
def on_shutdown(h):
"""
@ -226,7 +227,7 @@ def init_node(name, argv=sys.argv, anonymous=False, log_level=INFO, disable_rost
logger = logging.getLogger("rospy.client")
logger.info("init_node, name[%s], pid[%s]", resolved_node_name, os.getpid())
node = rospy.init.start_node(os.environ, resolved_node_name) #node initialization blocks until registration with master
node = rospy.impl.init.start_node(os.environ, resolved_node_name) #node initialization blocks until registration with master
timeout_t = time.time() + TIMEOUT_READY
code = None
@ -251,12 +252,12 @@ def init_node(name, argv=sys.argv, anonymous=False, log_level=INFO, disable_rost
logger.error("ROS node initialization failed: %s, %s, %s", code, msg, master_uri)
raise rospy.exceptions.ROSInitException("ROS node initialization failed: %s, %s, %s", code, msg, master_uri)
rospy.rosout.load_rosout_handlers(log_level)
rospy.impl.rosout.load_rosout_handlers(log_level)
if not disable_rosout:
rospy.rosout.init_rosout()
rospy.impl.rosout.init_rosout()
logdebug("init_node, name[%s], pid[%s]", resolved_node_name, os.getpid())
if not disable_rostime:
if not rospy.simtime.init_simtime():
if not rospy.impl.simtime.init_simtime():
raise rospy.exceptions.ROSInitException("Failed to initialize time. Please check logs for additional details")
else:
rospy.rostime.set_rostime_initialized(True)

View File

@ -55,7 +55,7 @@ import roslib.roslogging
import rospy.exceptions
from rospy.names import *
from rospy.validators import ParameterInvalid
from rospy.impl.validators import ParameterInvalid
_logger = logging.getLogger("rospy.core")

View File

View File

@ -45,11 +45,12 @@ import time
import roslib.rosenv
import rospy.core
import rospy.masterslave
import rospy.msnode
import rospy.msproxy
import rospy.names
import rospy.tcpros
import rospy.impl.tcpros
import rospy.impl.msnode
import rospy.impl.masterslave
DEFAULT_NODE_PORT = 0 #bind to any open port
DEFAULT_MASTER_PORT=11311 #default port for master's to bind to
@ -83,8 +84,8 @@ def _sub_start_node(environ, resolved_name, master_uri=None, port=DEFAULT_NODE_P
if not master_uri:
master_uri = default_master_uri()
handler = rospy.masterslave.ROSHandler(resolved_name, master_uri)
node = rospy.msnode.ROSNode(resolved_name, port, handler)
handler = rospy.impl.masterslave.ROSHandler(resolved_name, master_uri)
node = rospy.impl.msnode.ROSNode(resolved_name, port, handler)
node.start()
while not node.uri and not rospy.core.is_shutdown():
time.sleep(0.00001) #poll for XMLRPC init
@ -111,7 +112,7 @@ def start_node(environ, resolved_name, master_uri=None, port=None):
@rtype rospy.msproxy.NodeProxy
"""
global _node
rospy.tcpros.init_tcpros()
rospy.impl.tcpros.init_tcpros()
if _node is not None:
raise Exception("Only one master/slave can be run per instance (multiple calls to start_node)")
_node = _sub_start_node(environ, resolved_name, master_uri, port)

View File

@ -63,13 +63,14 @@ import urlparse
from roslib.xmlrpc import XmlRpcHandler
import rospy.names
import rospy.paramserver
import rospy.rostime
import rospy.tcpros
import rospy.impl.tcpros
from rospy.core import *
from rospy.registration import RegManager, get_topic_manager
from rospy.validators import non_empty, ParameterInvalid
from rospy.impl.paramserver import get_param_server_cache
from rospy.impl.registration import RegManager, get_topic_manager
from rospy.impl.validators import non_empty, ParameterInvalid
NUM_WORKERS = 3 #number of threads we use to send publisher_update notifications
@ -84,7 +85,7 @@ VAL = 2
def is_publishers_list(paramName):
return ('is_publishers_list', paramName)
_logger = logging.getLogger("rospy.masterslave")
_logger = logging.getLogger("rospy.impl.masterslave")
LOG_API = True
@ -183,7 +184,7 @@ class ROSHandler(XmlRpcHandler):
# initialize protocol handlers. The master will not have any.
self.protocol_handlers = []
handler = rospy.tcpros.get_tcpros_handler()
handler = rospy.impl.tcpros.get_tcpros_handler()
if handler is not None:
self.protocol_handlers.append(handler)
@ -464,7 +465,7 @@ class ROSHandler(XmlRpcHandler):
@rtype: [int, str, int]
"""
try:
rospy.paramserver.get_param_server_cache().update(parameter_key, parameter_value)
get_param_server_cache().update(parameter_key, parameter_value)
return 1, '', 0
except KeyError:
return -1, 'not subscribed', 0

View File

@ -42,8 +42,9 @@ import threading
import time
import traceback
import rospy.core
from rospy.core import is_shutdown, xmlrpcapi, logfatal, logwarn, loginfo, logerr, logdebug
from rospy.core import is_shutdown, xmlrpcapi, \
logfatal, logwarn, loginfo, logerr, logdebug, \
signal_shutdown, add_preshutdown_hook
from rospy.names import get_caller_id, get_namespace
# topic manager and service manager singletons
@ -183,7 +184,7 @@ class RegManager(RegistrationListener):
self.cond = threading.Condition() #for locking/notifying updates
self.registered = False
# cleanup has to occur before official shutdown
rospy.core.add_preshutdown_hook(self.cleanup)
add_preshutdown_hook(self.cleanup)
def start(self, uri, master_uri):
"""
@ -223,13 +224,13 @@ class RegManager(RegistrationListener):
code, msg, val = master.registerPublisher(caller_id, resolved_name, data_type, uri)
if code != 1:
logfatal("cannot register publication topic [%s] with master: %s"%(resolved_name, msg))
rospy.core.signal_shutdown("master/node incompatibility with register publisher")
signal_shutdown("master/node incompatibility with register publisher")
for resolved_name, data_type in sub:
self.logger.info("registering subscriber topic [%s] type [%s] with master", resolved_name, data_type)
code, msg, val = master.registerSubscriber(caller_id, resolved_name, data_type, uri)
if code != 1:
logfatal("cannot register subscription topic [%s] with master: %s"%(resolved_name, msg))
rospy.core.signal_shutdown("master/node incompatibility with register subscriber")
signal_shutdown("master/node incompatibility with register subscriber")
else:
self.publisher_update(resolved_name, val)
for resolved_name, service_uri in srv:
@ -237,7 +238,7 @@ class RegManager(RegistrationListener):
code, msg, val = master.registerService(caller_id, resolved_name, service_uri, uri)
if code != 1:
logfatal("cannot register service [%s] with master: %s"%(resolved_name, msg))
rospy.core.signal_shutdown("master/node incompatibility with register service")
signal_shutdown("master/node incompatibility with register service")
registered = True

View File

@ -42,9 +42,10 @@ import rospy.names
from rospy.core import add_log_handler, get_caller_id
from rospy.exceptions import ROSException
from rospy.registration import get_topic_manager
from rospy.rostime import Time
from rospy.topics import Publisher, Subscriber
from rospy.rostime import Time
from rospy.impl.registration import get_topic_manager
#Log message for rosout
import roslib.msg

View File

@ -42,17 +42,17 @@ The rospy tcpros implementation is split into three areas:
- L{rospy.tcpros_service}: Service-specific capabilities
"""
import rospy.tcpros_base
import rospy.tcpros_pubsub
import rospy.tcpros_service
import rospy.impl.tcpros_service
_handler = rospy.tcpros_pubsub.TCPROSHandler()
from rospy.impl.tcpros_base import init_tcpros_server, DEFAULT_BUFF_SIZE
from rospy.impl.tcpros_pubsub import TCPROSHandler
_handler = TCPROSHandler()
DEFAULT_BUFF_SIZE = rospy.tcpros_base.DEFAULT_BUFF_SIZE
def init_tcpros():
server = rospy.tcpros_base.init_tcpros_server()
server = init_tcpros_server()
server.topic_connection_handler = _handler.topic_connection_handler
server.service_connection_handler = rospy.tcpros_service.service_connection_handler
server.service_connection_handler = rospy.impl.tcpros_service.service_connection_handler
def get_tcpros_handler():
return _handler

View File

@ -52,9 +52,10 @@ from rospy.core import *
from rospy.core import logwarn, loginfo, logerr, logdebug, rospydebug, rospyerr, rospywarn
from rospy.exceptions import ROSInternalException, TransportException, TransportTerminated, TransportInitError
from rospy.msg import deserialize_messages, serialize_message
from rospy.transport import Transport, BIDIRECTIONAL
from rospy.service import ServiceException
from rospy.impl.transport import Transport, BIDIRECTIONAL
logger = logging.getLogger('rospy.tcpros')
# Receive buffer size for topics/services (in bytes)

View File

@ -40,10 +40,11 @@ import threading
from rospy.core import logwarn, logerr, logdebug
import rospy.exceptions
import rospy.names
import rospy.registration
import rospy.transport
from rospy.tcpros_base import TCPROSTransport, TCPROSTransportProtocol, \
import rospy.impl.registration
import rospy.impl.transport
from rospy.impl.tcpros_base import TCPROSTransport, TCPROSTransportProtocol, \
get_tcpros_server_address, start_tcpros_server,\
DEFAULT_BUFF_SIZE, TCPROS
@ -76,7 +77,7 @@ class TCPROSSub(TCPROSTransportProtocol):
@type tcp_nodelay: bool
"""
super(TCPROSSub, self).__init__(resolved_name, recv_data_class, queue_size, buff_size)
self.direction = rospy.transport.INBOUND
self.direction = rospy.impl.transport.INBOUND
self.tcp_nodelay = tcp_nodelay
def get_header_fields(self):
@ -128,7 +129,7 @@ class TCPROSPub(TCPROSTransportProtocol):
# very small buffer size for publishers as the messages they receive are very small
super(TCPROSPub, self).__init__(resolved_name, None, queue_size=None, buff_size=128)
self.pub_data_class = pub_data_class
self.direction = rospy.transport.OUTBOUND
self.direction = rospy.impl.transport.OUTBOUND
self.is_latch = is_latch
self.headers = headers if headers else {}
@ -147,7 +148,7 @@ class TCPROSPub(TCPROSTransportProtocol):
base.update(self.headers)
return base
class TCPROSHandler(rospy.transport.ProtocolHandler):
class TCPROSHandler(rospy.impl.transport.ProtocolHandler):
"""
ROS Protocol handler for TCPROS. Accepts both TCPROS topic
connections as well as ROS service connections over TCP. TCP server
@ -197,7 +198,7 @@ class TCPROSHandler(rospy.transport.ProtocolHandler):
return 0, "INTERNAL ERROR: protocol id is not TCPROS: %s"%id, 0
id, dest_addr, dest_port = protocol_params
sub = rospy.registration.get_topic_manager().get_subscriber_impl(resolved_name)
sub = rospy.impl.registration.get_topic_manager().get_subscriber_impl(resolved_name)
#Create connection
try:
@ -277,7 +278,7 @@ class TCPROSHandler(rospy.transport.ProtocolHandler):
else:
resolved_topic_name = header['topic']
md5sum = header['md5sum']
tm = rospy.registration.get_topic_manager()
tm = rospy.impl.registration.get_topic_manager()
topic = tm.get_publisher_impl(resolved_topic_name)
if not topic:
return "[%s] is not a publisher of [%s]. Topics are %s"%(rospy.names.get_caller_id(), resolved_topic_name, tm.get_publications())

View File

@ -46,9 +46,10 @@ import traceback
import roslib.scriptutil
from rospy.exceptions import TransportInitError, TransportTerminated, ROSException, ROSInterruptException
from rospy.registration import get_service_manager
from rospy.service import _Service, ServiceException
from rospy.tcpros_base import TCPROSTransport, TCPROSTransportProtocol, \
from rospy.impl.registration import get_service_manager
from rospy.impl.tcpros_base import TCPROSTransport, TCPROSTransportProtocol, \
get_tcpros_server_address, start_tcpros_server, recv_buff, \
DEFAULT_BUFF_SIZE
@ -56,7 +57,8 @@ from rospy.core import logwarn, loginfo, logerr, logdebug
import rospy.core
import rospy.msg
import rospy.names
import rospy.validators
import rospy.impl.validators
logger = logging.getLogger('rospy.service')
@ -430,7 +432,7 @@ class ServiceProxy(_Service):
# validate
try:
rospy.core.parse_rosrpc_uri(self.uri)
except rospy.validators.ParameterInvalid:
except rospy.impl.validators.ParameterInvalid:
raise ServiceException("master returned invalid ROSRPC URI: %s"%self.uri)
except socket.error, e:
logger.error("[%s]: socket error contacting service, master is probably unavailable",self.resolved_name)

View File

@ -40,8 +40,8 @@ UDPROS connection protocol.
import roslib.network
import rospy.registration
import rospy.transport
import rospy.impl.registration
import rospy.impl.transport
def get_max_datagram_size():
#TODO

View File

@ -41,9 +41,10 @@ dictionary accessors on the parameter server.
import rospy.core
import rospy.exceptions
import rospy.masterslave
import rospy.names
import rospy.paramserver
import rospy.impl.paramserver
import rospy.impl.masterslave
class NodeProxy(object):
"""
@ -57,7 +58,7 @@ class NodeProxy(object):
def __getattr__(self, key): #forward api calls to target
f = getattr(self.target, key)
remappings = rospy.masterslave.ROSHandler.remappings(key)
remappings = rospy.impl.masterslave.ROSHandler.remappings(key)
def wrappedF(*args, **kwds):
args = [rospy.names.get_caller_id(),]+list(args)
#print "Remap indicies", remappings
@ -112,7 +113,7 @@ class MasterProxy(NodeProxy):
if key in _master_arg_remap:
remappings = _master_arg_remap[key]
else:
remappings = rospy.masterslave.ROSHandler.remappings(key)
remappings = rospy.impl.masterslave.ROSHandler.remappings(key)
def wrappedF(*args, **kwds):
args = [rospy.names.get_caller_id(),]+list(args)
#print "Remap indicies", remappings
@ -141,14 +142,14 @@ class MasterProxy(NodeProxy):
try:
# check for value in the parameter server cache
return rospy.paramserver.get_param_server_cache().get(resolved_key)
return rospy.impl.paramserver.get_param_server_cache().get(resolved_key)
except KeyError:
# first access, make call to parameter server
code, msg, value = self.target.subscribeParam(rospy.names.get_caller_id(), rospy.core.get_node_uri(), resolved_key)
if code != 1: #unwrap value with Python semantics
raise KeyError(key)
# set the value in the cache so that it's marked as subscribed
rospy.paramserver.get_param_server_cache().set(resolved_key, value)
rospy.impl.paramserver.get_param_server_cache().set(resolved_key, value)
return value
def __setitem__(self, key, val):
@ -194,7 +195,7 @@ class MasterProxy(NodeProxy):
raise rospy.exceptions.ROSException("cannot delete parameter: %s"%msg)
elif 0: #disable parameter cache
# set the value in the cache so that it's marked as subscribed
rospy.paramserver.get_param_server_cache().delete(resolved_key)
rospy.impl.paramserver.get_param_server_cache().delete(resolved_key)
def __contains__(self, key):
"""

View File

@ -48,7 +48,7 @@ from roslib.names import namespace, get_ros_namespace, ns_join, make_global_ns,
import roslib.names
from rospy.exceptions import ROSException
from rospy.validators import ParameterInvalid
from rospy.impl.validators import ParameterInvalid
TOPIC_ANYTYPE = ANYTYPE #indicates that a subscriber will connect any datatype given to it
SERVICE_ANYTYPE = ANYTYPE #indicates that a service client does not have a fixed type

View File

@ -39,8 +39,9 @@ import logging
import traceback
from rospy.core import *
from rospy.registration import set_service_manager, Registration, get_registration_listeners
from rospy.transport import *
from rospy.impl.registration import set_service_manager, Registration, get_registration_listeners
from rospy.impl.transport import *
logger = logging.getLogger('rospy.service')

View File

@ -73,9 +73,10 @@ import roslib.message
from rospy.core import *
from rospy.exceptions import ROSSerializationException, TransportTerminated
from rospy.msg import serialize_message, args_kwds_to_message
from rospy.registration import get_topic_manager, set_topic_manager, Registration, get_registration_listeners
from rospy.tcpros import get_tcpros_handler, DEFAULT_BUFF_SIZE
from rospy.transport import DeadTransport
from rospy.impl.registration import get_topic_manager, set_topic_manager, Registration, get_registration_listeners
from rospy.impl.tcpros import get_tcpros_handler, DEFAULT_BUFF_SIZE
from rospy.impl.transport import DeadTransport
_logger = logging.getLogger('rospy.topics')

View File

@ -45,8 +45,8 @@ class TestRospyMsnode(unittest.TestCase):
def test_ROSNode(self):
# mostly a trip wire test
import rospy.msnode
ROSNode = rospy.msnode.ROSNode
import rospy.impl.msnode
ROSNode = rospy.impl.msnode.ROSNode
node = ROSNode('/foo')
self.assertEquals('foo', node.name)
self.assertEquals(node.port, 0)
@ -63,4 +63,4 @@ class TestRospyMsnode(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyMsnode, coverage_packages=['rospy.msnode'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyMsnode, coverage_packages=['rospy.impl.msnode'])

View File

@ -51,7 +51,7 @@ from roslib.names import make_global_ns, ns_join
class TestRospyParamServer(unittest.TestCase):
def test_param_server_cache(self):
from rospy.paramserver import get_param_server_cache
from rospy.impl.paramserver import get_param_server_cache
ps = get_param_server_cache()
self.assert_(ps is not None)
try:
@ -81,4 +81,4 @@ class TestRospyParamServer(unittest.TestCase):
except KeyError: pass
if __name__ == '__main__':
rostest.unitrun('test_rospy', sys.argv[0], TestRospyParamServer, coverage_packages=['rospy.paramserver'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyParamServer, coverage_packages=['rospy.impl.paramserver'])

View File

@ -45,9 +45,9 @@ import cStringIO
class TestRospyRegistration(unittest.TestCase):
def test_get_set_topic_manager(self):
from rospy.registration import get_topic_manager, set_topic_manager
from rospy.impl.registration import get_topic_manager, set_topic_manager
# rospy initialization sets this, but it is out of scope of
# rospy.registrations to test its value
# rospy.impl.registrations to test its value
orig = get_topic_manager()
try:
self.assert_(orig is not None)
@ -62,9 +62,9 @@ class TestRospyRegistration(unittest.TestCase):
set_topic_manager(orig)
def test_get_set_service_manager(self):
from rospy.registration import get_service_manager, set_service_manager
from rospy.impl.registration import get_service_manager, set_service_manager
# rospy initialization sets this, but it is out of scope of
# rospy.registrations to test its value
# rospy.impl.registrations to test its value
try:
orig = get_service_manager()
self.assert_(orig is not None)
@ -80,7 +80,7 @@ class TestRospyRegistration(unittest.TestCase):
def test_Registration(self):
# nothing to test here really
from rospy.registration import Registration
from rospy.impl.registration import Registration
self.assertEquals('pub', Registration.PUB)
self.assertEquals('sub', Registration.SUB)
self.assertEquals('srv', Registration.SRV)
@ -89,14 +89,14 @@ class TestRospyRegistration(unittest.TestCase):
self.assertEquals('sub', r.SUB)
self.assertEquals('srv', r.SRV)
def test_RegistrationListener(self):
from rospy.registration import RegistrationListener
from rospy.impl.registration import RegistrationListener
#RegistrationListener is just an API, nothing to test here
l = RegistrationListener()
l.reg_added('name', 'data_type', 'reg_type')
l.reg_removed('name', 'data_type', 'reg_type')
def test_RegistrationListeners(self):
from rospy.registration import _RegistrationListeners, RegistrationListener
from rospy.impl.registration import _RegistrationListeners, RegistrationListener
class Mock(RegistrationListener):
def __init__(self):
@ -162,12 +162,12 @@ class TestRospyRegistration(unittest.TestCase):
self.assertEquals(['removed', 'n4', 'dtype4', 'rtype4'], l1.args)
def test_get_registration_listeners(self):
from rospy.registration import _RegistrationListeners, get_registration_listeners
from rospy.impl.registration import _RegistrationListeners, get_registration_listeners
r = get_registration_listeners()
self.assert_(isinstance(r, _RegistrationListeners))
def test_RegManager(self):
from rospy.registration import RegManager
from rospy.impl.registration import RegManager
class MockHandler(object):
def __init__(self):
self.done = False
@ -246,7 +246,7 @@ class TestRospyRegistration(unittest.TestCase):
# - test with is_shutdown overriden so we don't enter loop
def foo():
return True
sys.modules['rospy.registration'].__dict__['is_shutdown'] = foo
sys.modules['rospy.impl.registration'].__dict__['is_shutdown'] = foo
m.start('http://localhost:1234', 'http://localhost:4567')
handler.done = True
@ -261,4 +261,4 @@ class TestRospyRegistration(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyRegistration, coverage_packages=['rospy.registration'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyRegistration, coverage_packages=['rospy.impl.registration'])

View File

@ -56,7 +56,7 @@ class TestRospyTime(unittest.TestCase):
def test_import_simtime(self):
# trip wire test, make sure the module is loading
import rospy.simtime
import rospy.impl.simtime
# can't actually do unit tests of simtime, requires rostest
def test_switch_to_wallclock(self):
@ -366,4 +366,4 @@ def backwards_sleeper():
test_backwards_sleep_done = True
if __name__ == '__main__':
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTime, coverage_packages=['rospy.rostime', 'rospy.simtime', 'rospy.client'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTime, coverage_packages=['rospy.rostime', 'rospy.impl.simtime', 'rospy.client'])

View File

@ -44,16 +44,16 @@ import time
class TestRospyTcpros(unittest.TestCase):
def test_init_tcpros(self):
import rospy.tcpros
rospy.tcpros.init_tcpros()
import rospy.impl.tcpros
rospy.impl.tcpros.init_tcpros()
# nothing to validate here other than make sure no exceptions
def test_syms(self):
import rospy.tcpros
import rospy.transport
self.assertEquals(int, type(rospy.tcpros.DEFAULT_BUFF_SIZE))
self.assert_(isinstance(rospy.tcpros.get_tcpros_handler(), rospy.transport.ProtocolHandler))
import rospy.impl.tcpros
import rospy.impl.transport
self.assertEquals(int, type(rospy.impl.tcpros.DEFAULT_BUFF_SIZE))
self.assert_(isinstance(rospy.impl.tcpros.get_tcpros_handler(), rospy.impl.transport.ProtocolHandler))
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTcpros, coverage_packages=['rospy.tcpros'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTcpros, coverage_packages=['rospy.impl.tcpros'])

View File

@ -60,18 +60,18 @@ class MockEmptySock:
class TestRospyTcprosBase(unittest.TestCase):
def test_constants(self):
self.assertEquals("TCPROS", rospy.tcpros_base.TCPROS)
self.assert_(type(rospy.tcpros_base.DEFAULT_BUFF_SIZE), int)
self.assertEquals("TCPROS", rospy.impl.tcpros_base.TCPROS)
self.assert_(type(rospy.impl.tcpros_base.DEFAULT_BUFF_SIZE), int)
def test_recv_buff(self):
from rospy.tcpros_base import recv_buff
from rospy.impl.tcpros_base import recv_buff
buff = cStringIO.StringIO()
try:
recv_buff(MockEmptySock(), buff, 1)
self.fail("recv_buff should have raised TransportTerminated")
except rospy.tcpros_base.TransportTerminated:
except rospy.impl.tcpros_base.TransportTerminated:
self.assertEquals('', buff.getvalue())
self.assertEquals(5, recv_buff(MockSock('1234567890'), buff, 5))
@ -82,7 +82,7 @@ class TestRospyTcprosBase(unittest.TestCase):
self.assertEquals('1234567890', buff.getvalue())
def test_TCPServer(self):
from rospy.tcpros_base import TCPServer
from rospy.impl.tcpros_base import TCPServer
def handler(sock, addr):
pass
s = None
@ -102,15 +102,15 @@ class TestRospyTcprosBase(unittest.TestCase):
import rospy
import random
from rospy.tcpros_base import TCPROSTransportProtocol
from rospy.transport import BIDIRECTIONAL
from rospy.impl.tcpros_base import TCPROSTransportProtocol
from rospy.impl.transport import BIDIRECTIONAL
p = TCPROSTransportProtocol('Bob', rospy.AnyMsg)
self.assertEquals('Bob', p.resolved_name)
self.assertEquals(rospy.AnyMsg, p.recv_data_class)
self.assertEquals(BIDIRECTIONAL, p.direction)
self.assertEquals({}, p.get_header_fields())
self.assertEquals(rospy.tcpros_base.DEFAULT_BUFF_SIZE, p.buff_size)
self.assertEquals(rospy.impl.tcpros_base.DEFAULT_BUFF_SIZE, p.buff_size)
v = random.randint(1, 100)
p = TCPROSTransportProtocol('Bob', rospy.AnyMsg, queue_size=v)
@ -121,16 +121,16 @@ class TestRospyTcprosBase(unittest.TestCase):
self.assertEquals(v, p.buff_size)
def test_TCPROSTransport(self):
import rospy.tcpros_base
from rospy.tcpros_base import TCPROSTransport, TCPROSTransportProtocol
from rospy.transport import OUTBOUND
import rospy.impl.tcpros_base
from rospy.impl.tcpros_base import TCPROSTransport, TCPROSTransportProtocol
from rospy.impl.transport import OUTBOUND
p = TCPROSTransportProtocol('Bob', rospy.AnyMsg)
p.direction = OUTBOUND
try:
TCPROSTransport(p, '')
self.fail("TCPROSTransport should not accept bad name")
except rospy.tcpros_base.TransportInitError: pass
except rospy.impl.tcpros_base.TransportInitError: pass
t = TCPROSTransport(p, 'transport-name')
self.assert_(t.socket is None)
@ -156,4 +156,4 @@ class TestRospyTcprosBase(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTcprosBase, coverage_packages=['rospy.tcpros_base'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTcprosBase, coverage_packages=['rospy.impl.tcpros_base'])

View File

@ -65,8 +65,8 @@ class FakeSocket(object):
class TestRospyTcprosPubsub(unittest.TestCase):
def test_TCPROSSub(self):
import rospy.transport
from rospy.tcpros_pubsub import TCPROSSub
import rospy.impl.transport
from rospy.impl.tcpros_pubsub import TCPROSSub
import test_rospy.msg
callerid = 'test_TCPROSSub'
@ -78,7 +78,7 @@ class TestRospyTcprosPubsub(unittest.TestCase):
recv_data_class = test_rospy.msg.Val
s = TCPROSSub(name, recv_data_class)
self.assertEquals(name, s.resolved_name)
self.assertEquals(rospy.transport.INBOUND, s.direction)
self.assertEquals(rospy.impl.transport.INBOUND, s.direction)
self.assertEquals(recv_data_class, s.recv_data_class)
self.assert_(s.buff_size > -1)
self.failIf(s.tcp_nodelay)
@ -105,8 +105,8 @@ class TestRospyTcprosPubsub(unittest.TestCase):
self.assertEquals('1', s.get_header_fields()['tcp_nodelay'])
def test_TCPROSPub(self):
import rospy.transport
from rospy.tcpros_pubsub import TCPROSPub
import rospy.impl.transport
from rospy.impl.tcpros_pubsub import TCPROSPub
import test_rospy.msg
callerid = 'test_TCPROSPub'
@ -118,7 +118,7 @@ class TestRospyTcprosPubsub(unittest.TestCase):
pub_data_class = test_rospy.msg.Val
p = TCPROSPub(name, pub_data_class)
self.assertEquals(name, p.resolved_name)
self.assertEquals(rospy.transport.OUTBOUND, p.direction)
self.assertEquals(rospy.impl.transport.OUTBOUND, p.direction)
self.assertEquals(pub_data_class, p.pub_data_class)
self.assert_(p.buff_size > -1)
self.failIf(p.is_latch)
@ -145,7 +145,7 @@ class TestRospyTcprosPubsub(unittest.TestCase):
def test_configure_pub_socket(self):
# #1241 regression test to make sure that imports don't get messed up again
from rospy.tcpros_pubsub import _configure_pub_socket
from rospy.impl.tcpros_pubsub import _configure_pub_socket
import socket
sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
_configure_pub_socket(sock, True)
@ -157,8 +157,8 @@ class TestRospyTcprosPubsub(unittest.TestCase):
def test_TCPROSHandler_topic_connection_handler(self):
import rospy
from rospy.registration import Registration
from rospy.tcpros_pubsub import TCPROSHandler
from rospy.impl.registration import Registration
from rospy.impl.tcpros_pubsub import TCPROSHandler
import test_rospy.msg
handler = TCPROSHandler()
@ -181,7 +181,7 @@ class TestRospyTcprosPubsub(unittest.TestCase):
self.assert_(err)
# register '/foo-tch'
tm = rospy.registration.get_topic_manager()
tm = rospy.impl.registration.get_topic_manager()
impl = tm.acquire_impl(Registration.PUB, topic_name, data_class)
self.assert_(impl is not None)
@ -235,4 +235,4 @@ class TestRospyTcprosPubsub(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', 'test_rospy_tcpros_pubsub', TestRospyTcprosPubsub, coverage_packages=['rospy.tcpros_pubsub'])
rostest.unitrun('test_rospy', 'test_rospy_tcpros_pubsub', TestRospyTcprosPubsub, coverage_packages=['rospy.impl.tcpros_pubsub'])

View File

@ -66,7 +66,7 @@ class TestRospyTcprosService(unittest.TestCase):
def test_convert_return_to_response(self):
import rospy
from rospy.tcpros_service import convert_return_to_response
from rospy.impl.tcpros_service import convert_return_to_response
from test_ros.srv import AddTwoIntsResponse
cls = AddTwoIntsResponse
@ -139,11 +139,11 @@ class TestRospyTcprosService(unittest.TestCase):
def test_service_connection_handler(self):
import test_rospy.srv
from rospy.registration import get_service_manager
from rospy.impl.registration import get_service_manager
import rospy.service
sock = FakeSocket()
from rospy.tcpros_service import service_connection_handler
from rospy.impl.tcpros_service import service_connection_handler
client_addr = '10.0.0.1'
# check error conditions on missing headers
@ -177,8 +177,8 @@ class TestRospyTcprosService(unittest.TestCase):
def test_TCPROSServiceClient(self):
import rospy.transport
from rospy.tcpros_service import TCPROSServiceClient
import rospy.impl.transport
from rospy.impl.tcpros_service import TCPROSServiceClient
import test_rospy.srv
callerid = 'test_TCPROSServiceClient'
@ -190,7 +190,7 @@ class TestRospyTcprosService(unittest.TestCase):
srv_data_class = test_rospy.srv.EmptySrv
p = TCPROSServiceClient(name, srv_data_class)
self.assertEquals(name, p.resolved_name)
self.assertEquals(rospy.transport.BIDIRECTIONAL, p.direction)
self.assertEquals(rospy.impl.transport.BIDIRECTIONAL, p.direction)
self.assertEquals(srv_data_class, p.service_class)
self.assert_(p.buff_size > -1)
@ -212,8 +212,8 @@ class TestRospyTcprosService(unittest.TestCase):
def test_TCPService(self):
import rospy.transport
from rospy.tcpros_service import TCPService
import rospy.impl.transport
from rospy.impl.tcpros_service import TCPService
import test_rospy.srv
callerid = 'test_TCPService'
@ -225,7 +225,7 @@ class TestRospyTcprosService(unittest.TestCase):
srv_data_class = test_rospy.srv.EmptySrv
p = TCPService(name, srv_data_class)
self.assertEquals(name, p.resolved_name)
self.assertEquals(rospy.transport.BIDIRECTIONAL, p.direction)
self.assertEquals(rospy.impl.transport.BIDIRECTIONAL, p.direction)
self.assertEquals(srv_data_class, p.service_class)
self.assert_(p.buff_size > -1)
@ -240,4 +240,4 @@ class TestRospyTcprosService(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', 'test_rospy_tcpros_service', TestRospyTcprosService, coverage_packages=['rospy.tcpros_service'])
rostest.unitrun('test_rospy', 'test_rospy_tcpros_service', TestRospyTcprosService, coverage_packages=['rospy.impl.tcpros_service'])

View File

@ -47,10 +47,10 @@ def callback1(data): pass
def callback2(data): pass
# for use with publish() tests
import rospy.transport
class ConnectionOverride(rospy.transport.Transport):
import rospy.impl.transport
class ConnectionOverride(rospy.impl.transport.Transport):
def __init__(self, endpoint_id):
super(ConnectionOverride, self).__init__(rospy.transport.OUTBOUND, endpoint_id)
super(ConnectionOverride, self).__init__(rospy.impl.transport.OUTBOUND, endpoint_id)
self.endpoint_id = endpoint_id
self.data = ''
@ -63,7 +63,7 @@ class TestRospyTopics(unittest.TestCase):
def test_Publisher(self):
import rospy
from rospy.registration import get_topic_manager, Registration
from rospy.impl.registration import get_topic_manager, Registration
from rospy.topics import Publisher, DEFAULT_BUFF_SIZE
# Publisher(self, name, data_class, subscriber_listener=None, tcp_nodelay=False, latch=False, headers=None)
@ -209,7 +209,7 @@ class TestRospyTopics(unittest.TestCase):
#TODO: negative buff_size
#TODO: negative queue_size
import rospy
from rospy.registration import get_topic_manager, Registration
from rospy.impl.registration import get_topic_manager, Registration
from rospy.topics import Subscriber, DEFAULT_BUFF_SIZE
#Subscriber: name, data_class, callback=None, callback_args=None,

View File

@ -44,7 +44,7 @@ import time
class TestRospyTransport(unittest.TestCase):
def test_Transport(self):
from rospy.transport import Transport, INBOUND, OUTBOUND, BIDIRECTIONAL
from rospy.impl.transport import Transport, INBOUND, OUTBOUND, BIDIRECTIONAL
ids = []
for d in [INBOUND, OUTBOUND, BIDIRECTIONAL]:
t = Transport(d)
@ -103,7 +103,7 @@ class TestRospyTransport(unittest.TestCase):
except: pass
def test_DeadTransport(self):
from rospy.transport import Transport, DeadTransport, INBOUND, OUTBOUND, BIDIRECTIONAL
from rospy.impl.transport import Transport, DeadTransport, INBOUND, OUTBOUND, BIDIRECTIONAL
t = Transport(INBOUND, 'foo')
t.stat_bytes = 1234
t.stat_num_msg = 5678
@ -126,7 +126,7 @@ class TestRospyTransport(unittest.TestCase):
def test_ProtocolHandler(self):
# tripwire tests
from rospy.transport import ProtocolHandler
from rospy.impl.transport import ProtocolHandler
h = ProtocolHandler()
self.failIf(h.supports('TCPROS'))
self.assertEquals([], h.get_supported())
@ -142,4 +142,4 @@ class TestRospyTransport(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTransport, coverage_packages=['rospy.transport'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyTransport, coverage_packages=['rospy.impl.transport'])

View File

@ -45,12 +45,12 @@ class TestRospyValidators(unittest.TestCase):
def test_ParameterInvalid(self):
# not really testing anything here other than typos
from rospy.validators import ParameterInvalid
from rospy.impl.validators import ParameterInvalid
self.assert_(isinstance(ParameterInvalid('param'), Exception))
def test_validators(self):
from rospy.validators import ParameterInvalid
from rospy.validators import non_empty
from rospy.impl.validators import ParameterInvalid
from rospy.impl.validators import non_empty
contextes = ['', '/', '/foo']
for context in contextes:
valid = ['foo', 1, [1]]
@ -65,4 +65,4 @@ class TestRospyValidators(unittest.TestCase):
if __name__ == '__main__':
import rostest
rostest.unitrun('test_rospy', sys.argv[0], TestRospyValidators, coverage_packages=['rospy.validators'])
rostest.unitrun('test_rospy', sys.argv[0], TestRospyValidators, coverage_packages=['rospy.impl.validators'])