more epydoc updates
This commit is contained in:
parent
3d6a154bb0
commit
c1e71c4aea
|
@ -193,8 +193,9 @@ def check_type(field_name, field_type, field_val):
|
|||
# raise SerializationError('field [%s] must be a [%s] instance instead of a %s'%(field_name, field_type, type(field_val)))
|
||||
#TODO: dynamically load message class and do instance compare
|
||||
|
||||
##Base class of auto-generated message data objects.
|
||||
class Message(object):
|
||||
"""Base class of Message data classes auto-generated from msg files. """
|
||||
|
||||
# slots is explicitly both for data representation and
|
||||
# performance. Higher-level code assumes that there is a 1-to-1
|
||||
# mapping between __slots__ and message fields. In terms of
|
||||
|
@ -202,11 +203,14 @@ class Message(object):
|
|||
# new-style object.
|
||||
__slots__ = ['_connection_header']
|
||||
|
||||
## Message base constructor. Contains generic initializers for
|
||||
## args-based and kwds-based initialization of message fields,
|
||||
## assuming there is a one-to-one mapping between __slots__ and
|
||||
## message fields.
|
||||
def __init__(self, *args, **kwds):
|
||||
"""
|
||||
ctor. There are multiple ways of initializing Message
|
||||
instances, either using a 1-to-1 correspondence between
|
||||
constructor arguments and message fields (*args), or using
|
||||
Python "keyword" arguments (**kwds) to initialize named field
|
||||
and leave the rest with default values.
|
||||
"""
|
||||
if args and kwds:
|
||||
raise TypeError("Message constructor may only use args OR keywords, not both")
|
||||
if args:
|
||||
|
@ -245,8 +249,18 @@ class Message(object):
|
|||
raise SerializationError(str(exc))
|
||||
|
||||
def serialize(self, buff):
|
||||
"""
|
||||
Serialize data into buffer
|
||||
@param buff: buffer
|
||||
@type buff: StringIO
|
||||
"""
|
||||
pass
|
||||
def deserialize(self, str):
|
||||
"""
|
||||
Deserialize data in str into this instance
|
||||
@param str: serialized data
|
||||
@type str: str
|
||||
"""
|
||||
pass
|
||||
def __str__(self):
|
||||
return strify_message(self)
|
||||
|
@ -268,12 +282,16 @@ class Message(object):
|
|||
return False
|
||||
return True
|
||||
|
||||
class ServiceDefinition(object): pass #marker class for auto-generated code
|
||||
class ServiceDefinition(object):
|
||||
"""Base class of Service classes auto-generated from srv files"""
|
||||
pass
|
||||
|
||||
## Message deserialization error
|
||||
class DeserializationError(ROSMessageException): pass
|
||||
## Message serialization error
|
||||
class SerializationError(ROSMessageException): pass
|
||||
class DeserializationError(ROSMessageException):
|
||||
"""Message deserialization error"""
|
||||
pass
|
||||
class SerializationError(ROSMessageException):
|
||||
"""Message serialization error"""
|
||||
pass
|
||||
|
||||
# Utilities for rostopic/rosservice
|
||||
|
||||
|
|
|
@ -33,10 +33,10 @@
|
|||
# Revision $Id: msgspec.py 3357 2009-01-13 07:13:05Z jfaustwg $
|
||||
# $Author: jfaustwg $
|
||||
"""
|
||||
ROS Msg Description Language Spec
|
||||
ROS msg library for Python
|
||||
|
||||
Implements: U{http://ros.org/wiki/msg}
|
||||
"""
|
||||
## ROS Msg Description Language Spec
|
||||
## Implements: http://pr.willowgarage.com/wiki/ROS/Message_Description_Language
|
||||
|
||||
import cStringIO
|
||||
import os
|
||||
|
|
|
@ -32,9 +32,10 @@
|
|||
#
|
||||
# Revision $Id: srvspec.py 3357 2009-01-13 07:13:05Z jfaustwg $
|
||||
# $Author: jfaustwg $
|
||||
"""ROS Service Description Language Spec"""
|
||||
## ROS Service Description Language Spec
|
||||
# Implements http://pr.willowgarage.com/wiki/ROS/Message_Description_Language
|
||||
"""
|
||||
ROS Service Description Language Spec
|
||||
Implements U{http://ros.org/wiki/srv}
|
||||
"""
|
||||
|
||||
import os
|
||||
import re
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
<depend package="roslang"/>
|
||||
<export>
|
||||
<roslang cmake="${prefix}/cmake/rospy.cmake"/>
|
||||
<rosdoc builder="eepydoc"/>
|
||||
<rosdoc builder="epydoc"/>
|
||||
</export>
|
||||
</package>
|
||||
|
||||
|
|
|
@ -71,7 +71,7 @@ def on_shutdown(h):
|
|||
Register function to be called on shutdown. This function will be
|
||||
called before Node begins teardown.
|
||||
@param h: Function with zero args to be called on shutdown.
|
||||
@type h: fn()
|
||||
@type h: fn()
|
||||
"""
|
||||
|
||||
# wrap function to strip reason argument that gets passed in for internal use
|
||||
|
@ -127,11 +127,11 @@ def init_node(name, argv=sys.argv, anonymous=False, log_level=INFO, disable_rost
|
|||
this method are not reversible.
|
||||
|
||||
@param name: Node's name
|
||||
@type name: string
|
||||
@type name: string
|
||||
|
||||
@param argv: Command line arguments to this program. ROS reads
|
||||
these arguments to find renaming params. Defaults to sys.argv.
|
||||
@type argv: [str]
|
||||
@type argv: [str]
|
||||
|
||||
@param anonymous: if True, a name will be auto-generated for
|
||||
the node using name as the base. This is useful when you wish
|
||||
|
@ -139,23 +139,23 @@ def init_node(name, argv=sys.argv, anonymous=False, log_level=INFO, disable_rost
|
|||
their actual names (e.g. tools, guis). name will be used as the
|
||||
stem of the auto-generated name. NOTE: you cannot remap the name
|
||||
of an anonymous node.
|
||||
@type anonymous: bool
|
||||
@type anonymous: bool
|
||||
|
||||
@param log_level: log level for sending message to /rosout,
|
||||
which is INFO by default. For convenience, you may use
|
||||
rospy.DEBUG, rospy.INFO, rospy.ERROR, rospy.WARN, rospy.FATAL,
|
||||
@type log_level: int
|
||||
@type log_level: int
|
||||
|
||||
@param disable_signals: If True, rospy will not register its
|
||||
own signal handlers. You must set this flag if (a) you are unable
|
||||
to call init_node from the main thread and/or you are using rospy
|
||||
in an environment where you need to control your own signal
|
||||
handling (e.g. WX).
|
||||
@type disable_signals: bool
|
||||
@type disable_signals: bool
|
||||
|
||||
@param disable_rostime: for rostests only, suppresses
|
||||
automatic subscription to rostime
|
||||
@type disable_rostime: bool
|
||||
@type disable_rostime: bool
|
||||
|
||||
@raise ROSInitException: if initialization/registration fails
|
||||
"""
|
||||
|
@ -278,9 +278,9 @@ def wait_for_service(service, timeout=None):
|
|||
initialization code if your program depends on a
|
||||
service already running.
|
||||
@param service: name of service
|
||||
@type service: str
|
||||
@type service: str
|
||||
@param timeout: timeout time in seconds
|
||||
@type timeout: double
|
||||
@type timeout: double
|
||||
@raise ROSException: if specified timeout is exceeded
|
||||
"""
|
||||
def contact_service(service, timeout=10.0):
|
||||
|
@ -351,7 +351,7 @@ def get_param(param_name, default=_unspecified):
|
|||
"""
|
||||
Retrieve a parameter from the param server
|
||||
@param default: (optional) default value to return if key is not set
|
||||
@type default: any
|
||||
@type default: any
|
||||
@return: parameter value
|
||||
@rtype: XmlRpcLegalValue
|
||||
@raise ROSException: if parameter server reports an error
|
||||
|
@ -384,9 +384,9 @@ def set_param(param_name, param_value):
|
|||
"""
|
||||
Set a parameter on the param server
|
||||
@param param_name: parameter name
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@param param_value: parameter value
|
||||
@type param_value: XmlRpcLegalValue
|
||||
@type param_value: XmlRpcLegalValue
|
||||
@raise ROSException: if parameter server reports an error
|
||||
"""
|
||||
_init_param_server()
|
||||
|
@ -396,7 +396,7 @@ def search_param(param_name):
|
|||
"""
|
||||
Search for a parameter on the param server
|
||||
@param param_name: parameter name
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@raise ROSException: if parameter server reports an error
|
||||
"""
|
||||
_init_param_server()
|
||||
|
@ -406,7 +406,7 @@ def delete_param(param_name):
|
|||
"""
|
||||
Delete a parameter on the param server
|
||||
@param param_name: parameter name
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@raise ROSException: if parameter server reports an error
|
||||
"""
|
||||
_init_param_server()
|
||||
|
@ -416,7 +416,7 @@ def has_param(param_name):
|
|||
"""
|
||||
Test if parameter exists on the param server
|
||||
@param param_name: parameter name
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@raise ROSException: if parameter server reports an error
|
||||
"""
|
||||
_init_param_server()
|
||||
|
@ -437,7 +437,7 @@ class Rate(object):
|
|||
"""
|
||||
Constructor.
|
||||
@param hz: hz rate to determine sleeping
|
||||
@type hz: int
|
||||
@type hz: int
|
||||
"""
|
||||
# #1403
|
||||
self.last_time = rospy.rostime.get_rostime()
|
||||
|
@ -474,7 +474,7 @@ def sleep(duration):
|
|||
is negative, sleep immediately returns.
|
||||
|
||||
@param duration: seconds (or rospy.Duration) to sleep
|
||||
@type duration: float or Duration
|
||||
@type duration: float or Duration
|
||||
@raise ROSInterruptException: if ROS time is set backwards or if
|
||||
ROS shutdown occurs before sleep completes
|
||||
"""
|
||||
|
|
|
@ -64,7 +64,7 @@ def mloginfo(msg, *args):
|
|||
Info-level master log statements. These statements may be printed
|
||||
to screen so they should be user-readable.
|
||||
@param msg: Message string
|
||||
@type msg: str
|
||||
@type msg: str
|
||||
@param args: arguments for msg if msg is a format string
|
||||
"""
|
||||
#mloginfo is in core so that it is accessible to master and masterdata
|
||||
|
@ -79,7 +79,7 @@ def mlogwarn(msg, *args):
|
|||
Warn-level master log statements. These statements may be printed
|
||||
to screen so they should be user-readable.
|
||||
@param msg: Message string
|
||||
@type msg: str
|
||||
@type msg: str
|
||||
@param args: arguments for msg if msg is a format string
|
||||
"""
|
||||
#mloginfo is in core so that it is accessible to master and masterdata
|
||||
|
@ -98,7 +98,7 @@ def parse_rosrpc_uri(uri):
|
|||
"""
|
||||
utility function for parsing ROS-RPC URIs
|
||||
@param uri: ROSRPC URI
|
||||
@type uri: str
|
||||
@type uri: str
|
||||
@return: address, port
|
||||
@rtype: (str, int)
|
||||
@raise ParameterInvalid: if uri is not a valid ROSRPC URI
|
||||
|
@ -136,9 +136,9 @@ def add_log_handler(level, h):
|
|||
"""
|
||||
Add handler for specified level
|
||||
@param level: log level (use constants from roslib.msg.Log)
|
||||
@type level: int
|
||||
@type level: int
|
||||
@param h: log message handler
|
||||
@type h: fn
|
||||
@type h: fn
|
||||
@raise ROSInternalException: if level is invalid
|
||||
"""
|
||||
if level == roslib.msg.Log.DEBUG:
|
||||
|
@ -251,7 +251,7 @@ def configure_logging(node_name):
|
|||
"""
|
||||
Setup filesystem logging for this node
|
||||
@param node_name: Node's name
|
||||
@type node_name str
|
||||
@type node_name str
|
||||
"""
|
||||
global _log_filename
|
||||
|
||||
|
@ -295,7 +295,7 @@ def set_initialized(initialized):
|
|||
"""
|
||||
set the initialization state of the local node
|
||||
@param initialized: True if node initialized
|
||||
@type initialized: bool
|
||||
@type initialized: bool
|
||||
"""
|
||||
global _client_ready
|
||||
_client_ready = initialized
|
||||
|
@ -338,7 +338,7 @@ def add_preshutdown_hook(h):
|
|||
Add method to invoke when system shuts down. Unlike X{add_shutdown_hook}, these
|
||||
methods will be called before any other shutdown hooks.
|
||||
@param h: function that takes in a single string argument (shutdown reason)
|
||||
@type h: fn(str)
|
||||
@type h: fn(str)
|
||||
"""
|
||||
_add_shutdown_hook(h, _preshutdown_hooks)
|
||||
|
||||
|
@ -352,7 +352,7 @@ def add_shutdown_hook(h):
|
|||
register client hooks.
|
||||
|
||||
@param h: function that takes in a single string argument (shutdown reason)
|
||||
@type h: fn(str)
|
||||
@type h: fn(str)
|
||||
"""
|
||||
_add_shutdown_hook(h, _shutdown_hooks)
|
||||
|
||||
|
@ -361,7 +361,7 @@ def signal_shutdown(reason):
|
|||
Initiates shutdown process by singaling objects waiting on _shutdown_lock.
|
||||
Shutdown and pre-shutdown hooks are invoked.
|
||||
@param reason: human-readable shutdown reason, if applicable
|
||||
@type reason: str
|
||||
@type reason: str
|
||||
"""
|
||||
global _shutdown_flag, _shutdown_lock, _shutdown_hooks
|
||||
_logger.info("signal_shutdown [%s]"%reason)
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
"""
|
||||
ROSPY initialization
|
||||
Internal use: rospy initialization.
|
||||
|
||||
This is mainly routines for initializing the master or slave based on
|
||||
the OS environment.
|
||||
|
@ -120,13 +120,13 @@ def start_node(environ, name, master_uri=None, port=None):
|
|||
"""
|
||||
Load ROS slave node, initialize from environment variables
|
||||
@param environ: environment variables
|
||||
@type environ: dict
|
||||
@type environ: dict
|
||||
@param name: override ROS_NODE: name of slave node
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param master_uri: override ROS_MASTER_URI: XMlRPC URI of central ROS server
|
||||
@type master_uri: str
|
||||
@type master_uri: str
|
||||
@param port: override ROS_PORT: port of slave xml-rpc node
|
||||
@type port: int
|
||||
@type port: int
|
||||
@return: node proxy instance
|
||||
@rtype rospy.msproxy.NodeProxy
|
||||
"""
|
||||
|
|
|
@ -102,7 +102,7 @@ def apivalidate(error_return_value, validators=()):
|
|||
arg. None means no validation for the parameter is required. As all
|
||||
api methods take caller_id as the first parameter, the validators
|
||||
start with the second param.
|
||||
@type validators: sequence
|
||||
@type validators: sequence
|
||||
"""
|
||||
def check_validates(f):
|
||||
assert len(validators) == f.func_code.co_argcount - 2, "%s failed arg check"%f #ignore self and caller_id
|
||||
|
@ -173,11 +173,11 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Base constructor for ROS nodes/masters
|
||||
@param name: ROS name of this node
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param master_uri: URI of master node, or None if this node is the master
|
||||
@type master_uri: str
|
||||
@type master_uri: str
|
||||
@param is_slave: True if this is a slave node, False if master
|
||||
@type is_slave: bool
|
||||
@type is_slave: bool
|
||||
"""
|
||||
super(ROSHandler, self).__init__()
|
||||
self.masterUri = master_uri
|
||||
|
@ -213,7 +213,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
def _ready(self, uri):
|
||||
"""
|
||||
@param uri: XML-RPC URI
|
||||
@type uri: str
|
||||
@type uri: str
|
||||
callback from ROSNode to inform handler of correct i/o information
|
||||
"""
|
||||
_logger.info("_ready: %s", uri)
|
||||
|
@ -226,13 +226,13 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Implements validation rules that require access to internal ROSHandler state.
|
||||
@param validation: name of validation rule to use
|
||||
@type validation: str
|
||||
@type validation: str
|
||||
@param param_name: name of parameter being validated
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@param param_value str: value of parameter
|
||||
@type param_value: str
|
||||
@type param_value: str
|
||||
@param caller_id: value of caller_id parameter to API method
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@raise ParameterInvalid: if the parameter does not meet validation
|
||||
@return: new value for parameter, after validation
|
||||
"""
|
||||
|
@ -258,7 +258,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
@internal
|
||||
@param cls: class to register remappings on
|
||||
@type cls: Class: class to register remappings on
|
||||
@type cls: Class: class to register remappings on
|
||||
@return: parameters (by pos) that should be remapped because they are names
|
||||
@rtype: list
|
||||
"""
|
||||
|
@ -295,7 +295,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Retrieve transport/topic statistics
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@return: [publishStats, subscribeStats, serviceStats]::
|
||||
publishStats: [[topicName, messageDataSent, pubConnectionData]...[topicNameN, messageDataSentN, pubConnectionDataN]]
|
||||
pubConnectionData: [connectionId, bytesSent, numSent, connected]* .
|
||||
|
@ -312,7 +312,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Retrieve transport/topic connection information
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
"""
|
||||
return 1, "bus info", get_topic_manager().get_pub_sub_info()
|
||||
|
||||
|
@ -321,7 +321,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Get the URI of the master node.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@return: [code, msg, masterUri]
|
||||
@rtype: [int, str, str]
|
||||
"""
|
||||
|
@ -333,7 +333,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
def _shutdown(self, reason=''):
|
||||
"""
|
||||
@param reason: human-readable debug string
|
||||
@type reason: str
|
||||
@type reason: str
|
||||
"""
|
||||
if not self.done:
|
||||
self.done = True
|
||||
|
@ -351,9 +351,9 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Stop this server
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param msg: a message describing why the node is being shutdown.
|
||||
@type msg: str
|
||||
@type msg: str
|
||||
@return: [code, msg, 0]
|
||||
@rtype: [int, str, int]
|
||||
"""
|
||||
|
@ -370,7 +370,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Get the PID of this server
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@return: [1, "", serverProcessPID]
|
||||
@rtype: [int, str, int]
|
||||
"""
|
||||
|
@ -392,7 +392,7 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Retrieve a list of topics that this node publishes.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@return: list of topics published by this node
|
||||
@rtype: [int, str, [ [topic1, topicType1]...[topicN, topicTypeN]]]
|
||||
"""
|
||||
|
@ -402,9 +402,9 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Connect subscriber to topic
|
||||
@param topic: topic name to connect
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param pub_uri: API URI of topic publisher
|
||||
@type pub_uri: str
|
||||
@type pub_uri: str
|
||||
@return: [code, msg, numConnects]. numConnects is the number
|
||||
of subscribers connected to the topic
|
||||
@rtype: [int, str, int]
|
||||
|
@ -458,11 +458,11 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Callback from master of current publisher list for specified topic.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param parameter_key str: parameter name, globally resolved
|
||||
@type parameter_key: str
|
||||
@type parameter_key: str
|
||||
@param parameter_value New parameter value
|
||||
@type parameter_value: XMLRPC-legal value
|
||||
@type parameter_value: XMLRPC-legal value
|
||||
@return: [code, status, ignore]. If code is -1 ERROR, the node
|
||||
is not subscribed to parameter_key
|
||||
@rtype: [int, str, int]
|
||||
|
@ -478,11 +478,11 @@ class ROSHandler(XmlRpcHandler):
|
|||
"""
|
||||
Callback from master of current publisher list for specified topic.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic str: topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param publishers: list of current publishers for topic in the form of XMLRPC URIs
|
||||
@type publishers: [str]
|
||||
@type publishers: [str]
|
||||
@return: [code, status, ignore]
|
||||
@rtype: [int, str, int]
|
||||
"""
|
||||
|
@ -503,14 +503,14 @@ class ROSHandler(XmlRpcHandler):
|
|||
establishing connection. For example, for a TCP/IP-based connection,
|
||||
the source node may return a port number of TCP/IP server.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic: topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param protocols: list of desired
|
||||
protocols for communication in order of preference. Each
|
||||
protocol is a list of the form [ProtocolName,
|
||||
ProtocolParam1, ProtocolParam2...N]
|
||||
@type protocols: [[str, XmlRpcLegalValue*]]
|
||||
@type protocols: [[str, XmlRpcLegalValue*]]
|
||||
@return: [code, msg, protocolParams]. protocolParams may be an
|
||||
empty list if there are no compatible protocols.
|
||||
@rtype: [int, str, [str, XmlRpcLegalValue*]]
|
||||
|
@ -589,7 +589,7 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Get the URI of the master(this) node.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@return: [code, msg, masterUri]
|
||||
@rtype: [int, str, str]
|
||||
"""
|
||||
|
@ -619,9 +619,9 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Parameter Server: delete parameter
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter name
|
||||
@type key: str
|
||||
@type key: str
|
||||
@return: [code, msg, 0]
|
||||
@rtype: [int, str, int]
|
||||
"""
|
||||
|
@ -648,11 +648,11 @@ class ROSMasterHandler(ROSHandler):
|
|||
parameters individually if you wish to perform a union update.
|
||||
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter name
|
||||
@type key: str
|
||||
@type key: str
|
||||
@param value: parameter value.
|
||||
@type value: XMLRPCLegalValue
|
||||
@type value: XMLRPCLegalValue
|
||||
@return: [code, msg, 0]
|
||||
@rtype: [int, str, int]
|
||||
"""
|
||||
|
@ -667,10 +667,10 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Retrieve parameter value from server.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter to lookup. If key is a namespace,
|
||||
getParam() will return a parameter tree.
|
||||
@type key: str
|
||||
@type key: str
|
||||
getParam() will return a parameter tree.
|
||||
|
||||
@return: [code, statusMessage, parameterValue]. If code is not
|
||||
|
@ -709,10 +709,10 @@ class ROSMasterHandler(ROSHandler):
|
|||
parameter does not exist (yet).
|
||||
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter to lookup. If key is a namespace,
|
||||
getParam() will return a parameter tree.
|
||||
@type key: str
|
||||
@type key: str
|
||||
@return: [code, statusMessage, foundKey]. If code is not 1, parameterValue should be
|
||||
ignored.
|
||||
@rtype: [int, str, str]
|
||||
|
@ -730,11 +730,11 @@ class ROSMasterHandler(ROSHandler):
|
|||
Retrieve parameter value from server and subscribe to updates to that param. See
|
||||
paramUpdate() in the Node API.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter to lookup.
|
||||
@type key: str
|
||||
@type key: str
|
||||
@param caller_api: API URI for paramUpdate callbacks.
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
@return: [code, statusMessage, parameterValue]. If code is not
|
||||
1, parameterValue should be ignored. parameterValue is an empty dictionary if the parameter
|
||||
has not been set yet.
|
||||
|
@ -757,11 +757,11 @@ class ROSMasterHandler(ROSHandler):
|
|||
Retrieve parameter value from server and subscribe to updates to that param. See
|
||||
paramUpdate() in the Node API.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter to lookup.
|
||||
@type key: str
|
||||
@type key: str
|
||||
@param str: API URI for paramUpdate callbacks.
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
@return: [code, statusMessage, numUnsubscribed]. If code is not
|
||||
If numUnsubscribed is zero it means that the caller was not subscribed to the parameter.
|
||||
@rtype: [int, str, XMLRPCLegalValue]
|
||||
|
@ -782,9 +782,9 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Check if parameter is stored on server.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param key: parameter to check
|
||||
@type key: str
|
||||
@type key: str
|
||||
@return: [code, statusMessage, hasParam]
|
||||
@rtype: [int, str, bool]
|
||||
"""
|
||||
|
@ -886,7 +886,7 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Register the caller as a provider of the specified service.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param service str: Fully-qualified name of service
|
||||
@param service_api str: Service URI
|
||||
@param caller_api str: XML-RPC URI of caller node
|
||||
|
@ -908,7 +908,7 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Lookup all provider of a particular service.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param service: fully-qualified name of service to lookup.
|
||||
@type: service: str
|
||||
@return (int, str, str): (code, message, serviceUrl). service URL is provides
|
||||
|
@ -930,12 +930,12 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Unregister the caller as a provider of the specified service.
|
||||
@param caller_id str: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param service: Fully-qualified name of service
|
||||
@type service: str
|
||||
@type service: str
|
||||
@param service_api: API URI of service to unregister. Unregistration will only occur if current
|
||||
registration matches.
|
||||
@type service_api: str
|
||||
@type service_api: str
|
||||
@return: (code, message, numUnregistered). Number of unregistrations (either 0 or 1).
|
||||
If this is zero it means that the caller was not registered as a service provider.
|
||||
The call still succeeds as the intended final state is reached.
|
||||
|
@ -962,12 +962,12 @@ class ROSMasterHandler(ROSHandler):
|
|||
a list of current publishers, the subscriber will also receive notifications
|
||||
of new publishers via the publisherUpdate API.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic str: Fully-qualified name of topic to subscribe to.
|
||||
@param topic_type: Datatype for topic. Must be a package-resource name, i.e. the .msg name.
|
||||
@type topic_type: str
|
||||
@type topic_type: str
|
||||
@param caller_api: XML-RPC URI of caller node for new publisher notifications
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
@return: (code, message, publishers). Publishers is a list of XMLRPC API URIs
|
||||
for nodes currently publishing the specified topic.
|
||||
@rtype: (int, str, list(str))
|
||||
|
@ -988,11 +988,11 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Unregister the caller as a publisher of the topic.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic: Fully-qualified name of topic to unregister.
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param caller_api: API URI of service to unregister. Unregistration will only occur if current
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
registration matches.
|
||||
@return: (code, statusMessage, numUnsubscribed).
|
||||
If numUnsubscribed is zero it means that the caller was not registered as a subscriber.
|
||||
|
@ -1013,14 +1013,14 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Register the caller as a publisher the topic.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic: Fully-qualified name of topic to register.
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param topic_type: Datatype for topic. Must be a
|
||||
package-resource name, i.e. the .msg name.
|
||||
@type topic_type: str
|
||||
@type topic_type: str
|
||||
@param caller_api str: ROS caller XML-RPC API URI
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
@return: (code, statusMessage, subscriberApis).
|
||||
List of current subscribers of topic in the form of XMLRPC URIs.
|
||||
@rtype: (int, str, [str])
|
||||
|
@ -1047,13 +1047,13 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Unregister the caller as a publisher of the topic.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param topic: Fully-qualified name of topic to unregister.
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param caller_api str: API URI of service to
|
||||
unregister. Unregistration will only occur if current
|
||||
registration matches.
|
||||
@type caller_api: str
|
||||
@type caller_api: str
|
||||
@return: (code, statusMessage, numUnregistered).
|
||||
If numUnregistered is zero it means that the caller was not registered as a publisher.
|
||||
The call still succeeds as the intended final state is reached.
|
||||
|
@ -1081,9 +1081,9 @@ class ROSMasterHandler(ROSHandler):
|
|||
publishers and subscribers. Use lookupService instead to lookup
|
||||
ROS-RPC URIs.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param node: name of node to lookup
|
||||
@type node: str
|
||||
@type node: str
|
||||
@return: (code, msg, URI)
|
||||
@rtype: (int, str, str)
|
||||
"""
|
||||
|
@ -1105,10 +1105,10 @@ class ROSMasterHandler(ROSHandler):
|
|||
Get list of topics that can be subscribed to. This does not return topics that have no publishers.
|
||||
See L{getSystemState()} to get more comprehensive list.
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param subgraph: Restrict topic names to match within the specified subgraph. Subgraph namespace
|
||||
is resolved relative to the caller's namespace. Use '' to specify all names.
|
||||
@type subgraph: str
|
||||
@type subgraph: str
|
||||
@return: (code, msg, [[topic1, type1]...[topicN, typeN]])
|
||||
@rtype: (int, str, [[str, str],])
|
||||
"""
|
||||
|
@ -1129,7 +1129,7 @@ class ROSMasterHandler(ROSHandler):
|
|||
"""
|
||||
Retrieve list representation of system state (i.e. publishers, subscribers, and services).
|
||||
@param caller_id: ROS caller id
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@rtype: (int, str, [[str,[str]], [str,[str]], [str,[str]]])
|
||||
@return: (code, statusMessage, systemState).
|
||||
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
## Support for ROS messages, including network serialization routines
|
||||
"""Internal use: Support for ROS messages, including network serialization routines"""
|
||||
|
||||
import time
|
||||
import struct
|
||||
|
@ -78,11 +78,11 @@ def serialize_message(b, seq, msg):
|
|||
"""
|
||||
Serialize the message to the buffer
|
||||
@param b: buffer to write to. WARNING: buffer will be reset after call
|
||||
@type b: StringIO
|
||||
@type b: StringIO
|
||||
@param msg: message to write
|
||||
@type msg: Msg
|
||||
@type msg: Msg
|
||||
@param seq: current sequence number (for headers)
|
||||
@type seq: int: current sequence number (for headers)
|
||||
@type seq: int: current sequence number (for headers)
|
||||
@raise ROSSerializationException: if unable to serialize
|
||||
message. This is usually due to a type error with one of the
|
||||
fields.
|
||||
|
@ -127,18 +127,18 @@ def deserialize_messages(b, msg_queue, data_class, queue_size=None, max_msgs=Non
|
|||
Read all messages off the buffer
|
||||
|
||||
@param b: buffer to read data from
|
||||
@type b: StringIO
|
||||
@type b: StringIO
|
||||
@param msg_queue: queue to append deserialized data to
|
||||
@type msg_queue: list
|
||||
@type msg_queue: list
|
||||
@param data_class: message deserialization class
|
||||
@type data_class: Message class
|
||||
@type data_class: Message class
|
||||
@param queue_size: message queue size. all but the last
|
||||
queue_size messages are discarded if this parameter is specified.
|
||||
@type queue_size: int
|
||||
@type queue_size: int
|
||||
@param start: starting position to read in b
|
||||
@type start: int
|
||||
@type start: int
|
||||
@param max_msgs int: maximum number of messages to deserialize or None
|
||||
@type max_msgs: int
|
||||
@type max_msgs: int
|
||||
@raise roslib.message.DeserializationError: if an error/exception occurs during deserialization
|
||||
"""
|
||||
try:
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
## ROSNode wraps the master/slave implementations in an XMLRPC API
|
||||
"""Internal use: contains the L{ROSNode} wrapper, which provides an unified interface for running an XMLRPC server for the rospy client library."""
|
||||
|
||||
import os
|
||||
import traceback
|
||||
|
|
|
@ -32,10 +32,11 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
"""
|
||||
Master/Slave XML-RPC Wrappers
|
||||
Master/Slave XML-RPC Wrappers.
|
||||
|
||||
Simplifies usage of master/slave APIs by automatically inserting caller ID
|
||||
and also adding python dictionary accessors on the parameter server.
|
||||
The L{NodeProxy} and L{MasterProxy} simplify usage of master/slave
|
||||
APIs by automatically inserting the caller ID and also adding python
|
||||
dictionary accessors on the parameter server.
|
||||
"""
|
||||
|
||||
import rospy.core
|
||||
|
|
|
@ -57,7 +57,7 @@ def canonicalize_name(name):
|
|||
Put name in canonical form. Double slashes '//' are removed and
|
||||
name is returned without any trailing slash, e.g. /foo/bar
|
||||
@param name: ROS name
|
||||
@type name: str
|
||||
@type name: str
|
||||
"""
|
||||
if not name or name == SEP:
|
||||
return name
|
||||
|
@ -90,13 +90,13 @@ def resolve_name(name, caller_id=None, remap=True):
|
|||
are resolved relative to the node name.
|
||||
|
||||
@param name: name to resolve.
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param caller_id: caller_id to resolve name relative to. To
|
||||
resolve to local namespace, omit this parameter (or use None)
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param remap: If False, remapping is turned off. This is mainly
|
||||
used to prevent circular remappings.
|
||||
@type remap: bool
|
||||
@type remap: bool
|
||||
@return: Resolved name. If name is empty/None, resolve_name
|
||||
returns parent namespace. If namespace is empty/None,
|
||||
@rtype: str
|
||||
|
@ -126,7 +126,7 @@ def remap_name(name, caller_id=None):
|
|||
resolve_name for APIs in which you don't wish to resolve the name
|
||||
unless it is remapped.
|
||||
@param name: name to remap
|
||||
@type name: str
|
||||
@type name: str
|
||||
@return: Remapped name
|
||||
@rtype: str
|
||||
"""
|
||||
|
@ -145,9 +145,9 @@ def scoped_name(caller_id, name):
|
|||
WARNING: scoped_name does not validate that name is actually within
|
||||
the supplied namespace.
|
||||
@param caller_id: caller ID, in canonical form
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
@param name: name to scope
|
||||
@type name: str
|
||||
@type name: str
|
||||
@return: name scoped to the caller_id's namespace.
|
||||
@rtype: str
|
||||
"""
|
||||
|
@ -199,10 +199,10 @@ def valid_name(param_name, resolve=True):
|
|||
"""
|
||||
Validator that resolves names and also ensures that they are not empty
|
||||
@param param_name: name
|
||||
@type param_name: str
|
||||
@type param_name: str
|
||||
@param resolve: if True/omitted, the name will be resolved to
|
||||
a global form. Otherwise, no resolution occurs.
|
||||
@type resolve: bool
|
||||
@type resolve: bool
|
||||
@return: resolved parameter value
|
||||
@rtype: str
|
||||
"""
|
||||
|
@ -274,7 +274,7 @@ def _set_caller_id(caller_id):
|
|||
The caller_id is important as it is the first parameter to any API
|
||||
call on a remote node. Invoked by ROSNode constructor
|
||||
@param caller_id: new caller ID
|
||||
@type caller_id: str
|
||||
@type caller_id: str
|
||||
"""
|
||||
global _caller_id, _caller_namespace
|
||||
_caller_id = caller_id
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""Internal use: handles maintaining registrations with master via internal listener APIs"""
|
||||
|
||||
import socket
|
||||
import sys
|
||||
import logging
|
||||
|
@ -44,8 +46,6 @@ import rospy.core
|
|||
from rospy.core import is_shutdown, xmlrpcapi, logfatal, logwarn, loginfo, logerr, logdebug
|
||||
from rospy.names import get_caller_id, get_namespace, resolve_name
|
||||
|
||||
"""Internal use: handles maintaining registrations with master via internal listener APIs"""
|
||||
|
||||
# topic manager and service manager singletons
|
||||
|
||||
_topic_manager = None
|
||||
|
@ -77,9 +77,9 @@ class RegistrationListener(object):
|
|||
New pub/sub/service declared.
|
||||
@param name: topic/service name
|
||||
@param data_type_or_uri: topic type or service uri
|
||||
@type data_type_or_uri: str
|
||||
@type data_type_or_uri: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
pass
|
||||
|
||||
|
@ -87,11 +87,11 @@ class RegistrationListener(object):
|
|||
"""
|
||||
New pub/sub/service removed.
|
||||
@param name: topic/service name
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_type_or_uri: topic type or service uri
|
||||
@type data_type_or_uri: str
|
||||
@type data_type_or_uri: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
pass
|
||||
|
||||
|
@ -110,7 +110,7 @@ class _RegistrationListeners(object):
|
|||
changes. This is an internal API used to notify higher level
|
||||
routines when to communicate with the master.
|
||||
@param l: listener to subscribe
|
||||
@type l: TopicListener
|
||||
@type l: TopicListener
|
||||
"""
|
||||
assert isinstance(l, RegistrationListener)
|
||||
try:
|
||||
|
@ -122,11 +122,11 @@ class _RegistrationListeners(object):
|
|||
def notify_removed(self, name, data_type_or_uri, reg_type):
|
||||
"""
|
||||
@param name: topic/service name
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_type_or_uri: topic type or service uri
|
||||
@type data_type_or_uri: str
|
||||
@type data_type_or_uri: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
try:
|
||||
self.lock.acquire()
|
||||
|
@ -141,11 +141,11 @@ class _RegistrationListeners(object):
|
|||
def notify_added(self, name, data_type, reg_type):
|
||||
"""
|
||||
@param name: topic/service name
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_type: topic/service type
|
||||
@type data_type: str
|
||||
@type data_type: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
try:
|
||||
self.lock.acquire()
|
||||
|
@ -189,9 +189,9 @@ class RegManager(RegistrationListener):
|
|||
Start the RegManager. This should be passed in as an argument to a thread
|
||||
starter as the RegManager is designed to spin in its own thread
|
||||
@param uri: URI of local node
|
||||
@type uri: str
|
||||
@type uri: str
|
||||
@param master_uri: Master URI
|
||||
@type master_uri: str
|
||||
@type master_uri: str
|
||||
"""
|
||||
self.registered = False
|
||||
self.master_uri = master_uri
|
||||
|
@ -315,7 +315,7 @@ class RegManager(RegistrationListener):
|
|||
"""
|
||||
Cleans up registrations with master and releases topic and service resources
|
||||
@param reason: human-reasonable debug string
|
||||
@type reason: str
|
||||
@type reason: str
|
||||
"""
|
||||
try:
|
||||
self.cond.acquire()
|
||||
|
@ -364,11 +364,11 @@ class RegManager(RegistrationListener):
|
|||
"""
|
||||
RegistrationListener callback
|
||||
@param name: name of topic or service
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_type_or_uri: either the data type (for topic regs) or the service URI (for service regs).
|
||||
@type data_type_or_uri: str
|
||||
@type data_type_or_uri: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
master_uri = self.master_uri
|
||||
if not master_uri:
|
||||
|
@ -389,11 +389,11 @@ class RegManager(RegistrationListener):
|
|||
"""
|
||||
RegistrationListener callback
|
||||
@param name: name of topic or service
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_type_or_uri: either the data type (for topic regs) or the service URI (for service regs).
|
||||
@type data_type_or_uri: str
|
||||
@type data_type_or_uri: str
|
||||
@param reg_type: Valid values are L{Registration.PUB}, L{Registration.SUB}, L{Registration.SRV}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
#TODO: this needs to be made robust to master outages
|
||||
master_uri = self.master_uri
|
||||
|
@ -441,9 +441,9 @@ class RegManager(RegistrationListener):
|
|||
will cause L{RegManager} to create a topic connection for all new
|
||||
publishers (in a separate thread).
|
||||
@param topic: Topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param uris: list of all publishers uris for topic
|
||||
@type uris: [str]
|
||||
@type uris: [str]
|
||||
"""
|
||||
try:
|
||||
self.cond.acquire()
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#
|
||||
# Revision $Id: client.py 2258 2008-09-30 23:03:06Z sfkwc $
|
||||
|
||||
## Internal use: support for /rosout logging in rospy
|
||||
"""Internal use: support for /rosout logging in rospy"""
|
||||
|
||||
import logging
|
||||
import sys
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#
|
||||
# Revision $Id: client.py 2258 2008-09-30 23:03:06Z sfkwc $
|
||||
|
||||
## ROS time and duration representations and API
|
||||
"""ROS time and duration representations, as well as internal routines for managing wallclock versus simulated time."""
|
||||
|
||||
import threading
|
||||
import time
|
||||
|
@ -88,7 +88,7 @@ class Time(roslib.rostime.Time):
|
|||
create new Time instance using time.time() value (float
|
||||
seconds)
|
||||
@param float_secs: time value in time.time() format
|
||||
@type float_secs: float
|
||||
@type float_secs: float
|
||||
@return: Time instance for specified time
|
||||
@rtype: L{Time}
|
||||
"""
|
||||
|
@ -134,7 +134,7 @@ def set_rostime_initialized(val):
|
|||
throw exceptions if rostime is being used before the underlying
|
||||
system is initialized.
|
||||
@param val: value for initialization state
|
||||
@type val: bool
|
||||
@type val: bool
|
||||
"""
|
||||
global _rostime_initialized
|
||||
_rostime_initialized = val
|
||||
|
|
|
@ -95,9 +95,9 @@ class ServiceManager(object):
|
|||
"""
|
||||
Register service with ServiceManager and ROS master
|
||||
@param service_name: name of service (resolved)
|
||||
@type service_name: str
|
||||
@type service_name: str
|
||||
@param service: Service to register
|
||||
@type service: L{_Service}
|
||||
@type service: L{_Service}
|
||||
"""
|
||||
err = None
|
||||
try:
|
||||
|
@ -119,9 +119,9 @@ class ServiceManager(object):
|
|||
"""
|
||||
Unregister service with L{ServiceManager} and ROS Master
|
||||
@param service_name: name of service
|
||||
@type service_name: str
|
||||
@type service_name: str
|
||||
@param service: service implementation
|
||||
@type service: L{_Service}
|
||||
@type service: L{_Service}
|
||||
"""
|
||||
try:
|
||||
self.lock.acquire()
|
||||
|
@ -137,7 +137,7 @@ class ServiceManager(object):
|
|||
def get_service(self, service_name):
|
||||
"""
|
||||
@param service_name: name of service
|
||||
@type service_name: str
|
||||
@type service_name: str
|
||||
@return: service implementation
|
||||
@rtype: _Service
|
||||
"""
|
||||
|
|
|
@ -33,24 +33,14 @@
|
|||
# Revision $Id$
|
||||
"""
|
||||
TCPROS connection protocol.
|
||||
|
||||
Implements: U{http://ros.org/wiki/ROS/TCPROS}
|
||||
|
||||
The rospy tcpros implementation is split into three areas:
|
||||
- L{rospy.tcpros_base}: common TCPROS routines, including header and connection processing
|
||||
- L{rospy.tcpros_pubsub}: Topic-specific capabilities for publishing and subscribing
|
||||
- L{rospy.tcpros_service}: Service-specific capabilities
|
||||
"""
|
||||
## TCPROS connection protocol.
|
||||
# http://pr.willowgarage.com/wiki/ROS/TCPROS
|
||||
#
|
||||
# TCPROS sets up a TCP/IP server socket on the source machine that
|
||||
# waits for incoming connections. When it receives an incoming
|
||||
# connection, it parses the header sent along the connection to
|
||||
# determine which topic it corresponds to. The format of this header
|
||||
# is:
|
||||
#
|
||||
# HEADER-LENGTH (32-bit int)
|
||||
# TOPIC-NAME (string identifier)
|
||||
# '\n' (newline character)
|
||||
# MSG-MD5SUM
|
||||
#
|
||||
# The MSG-MD5SUM is an md5sum of the full text of the .msg file. As
|
||||
# such, it will signal a version change even for compatible changes to
|
||||
# the file.
|
||||
|
||||
import rospy.tcpros_base
|
||||
import rospy.tcpros_pubsub
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#
|
||||
# Revision $Id: transport.py 2941 2008-11-26 03:19:48Z sfkwc $
|
||||
|
||||
"""Internal use: Topic-specific extensions for TCPROS support"""
|
||||
|
||||
import logging
|
||||
import socket
|
||||
import thread
|
||||
|
@ -46,26 +48,36 @@ from rospy.tcpros_base import TCPROSTransport, TCPROSTransportProtocol, \
|
|||
get_tcpros_server_address, start_tcpros_server,\
|
||||
DEFAULT_BUFF_SIZE, TCPROS
|
||||
|
||||
## Subscription transport implementation for receiving topic data via
|
||||
## peer-to-peer TCP/IP sockets
|
||||
class TCPROSSub(TCPROSTransportProtocol):
|
||||
"""Receive topic data via peer-to-peer TCP/IP sockets"""
|
||||
"""
|
||||
Subscription transport implementation for receiving topic data via
|
||||
peer-to-peer TCP/IP sockets
|
||||
"""
|
||||
|
||||
## ctor.
|
||||
## @param recv_data_class Message: class to instantiate to receive
|
||||
## messages
|
||||
## @param queue_size int: maximum number of messages to
|
||||
## deserialize from newly read data off socket
|
||||
## @param buff_size int: recv buffer size
|
||||
## @param tcp_nodelay bool: If True, request TCP_NODELAY from publisher
|
||||
def __init__(self, name, recv_data_class, queue_size=None, \
|
||||
buff_size=DEFAULT_BUFF_SIZE, tcp_nodelay=False):
|
||||
"""
|
||||
ctor.
|
||||
@param recv_data_class: class to instantiate to receive
|
||||
messages
|
||||
@type recv_data_class: L{rospy.Message}
|
||||
@param queue_size: maximum number of messages to
|
||||
deserialize from newly read data off socket
|
||||
@type queue_size: int
|
||||
@param buff_size: recv buffer size
|
||||
@type buff_size: int
|
||||
@param tcp_nodelay: If True, request TCP_NODELAY from publisher
|
||||
@type tcp_nodelay: bool
|
||||
"""
|
||||
super(TCPROSSub, self).__init__(name, recv_data_class, queue_size, buff_size)
|
||||
self.direction = rospy.transport.INBOUND
|
||||
self.tcp_nodelay = tcp_nodelay
|
||||
|
||||
## @return d dictionary of subscriber fields
|
||||
def get_header_fields(self):
|
||||
"""
|
||||
@return: dictionary of subscriber fields
|
||||
@rtype: dict
|
||||
"""
|
||||
return {'topic': self.name,
|
||||
'message_definition': self.recv_data_class._full_text,
|
||||
'tcp_nodelay': '1' if self.tcp_nodelay else '0',
|
||||
|
@ -74,10 +86,14 @@ class TCPROSSub(TCPROSTransportProtocol):
|
|||
'callerid': rospy.names.get_caller_id()}
|
||||
|
||||
# Separate method for easier testing
|
||||
## Configure socket options on a new publisher socket.
|
||||
## @param sock socket.socket
|
||||
## @param is_tcp_nodelay bool: if True, TCP_NODELAY will be set on outgoing socket if available
|
||||
def _configure_pub_socket(sock, is_tcp_nodelay):
|
||||
"""
|
||||
Configure socket options on a new publisher socket.
|
||||
@param sock: socket.socket
|
||||
@type sock: socket.socket
|
||||
@param is_tcp_nodelay: if True, TCP_NODELAY will be set on outgoing socket if available
|
||||
@param is_tcp_nodelay: bool
|
||||
"""
|
||||
# #956: low latency, TCP_NODELAY support
|
||||
if is_tcp_nodelay:
|
||||
if hasattr(socket, 'TCP_NODELAY'):
|
||||
|
@ -87,15 +103,22 @@ def _configure_pub_socket(sock, is_tcp_nodelay):
|
|||
|
||||
#TODO:POLLING: TCPROSPub currently doesn't actually do anything -- not until polling is implemented
|
||||
|
||||
## Publisher transport implementation for publishing topic data via
|
||||
## peer-to-peer TCP/IP sockets.
|
||||
class TCPROSPub(TCPROSTransportProtocol):
|
||||
"""Receive topic data via peer-to-peer TCP/IP sockets"""
|
||||
|
||||
## @param name str: topic name
|
||||
## @param pub_data_class Message class: class to instance to receive messages
|
||||
## @param is_latch bool: If True, Publisher is latching
|
||||
"""
|
||||
Publisher transport implementation for publishing topic data via
|
||||
peer-to-peer TCP/IP sockets.
|
||||
"""
|
||||
|
||||
def __init__(self, name, pub_data_class, is_latch=False, headers=None):
|
||||
"""
|
||||
ctor.
|
||||
@param name: topic name
|
||||
@type name: str
|
||||
@param pub_data_class: class to instance to receive messages
|
||||
@type pub_data_class: L{rospy.Message} class
|
||||
@param is_latch: If True, Publisher is latching
|
||||
@type is_latch: bool
|
||||
"""
|
||||
# very small buffer size for publishers as the messages they receive are very small
|
||||
super(TCPROSPub, self).__init__(name, None, queue_size=None, buff_size=128)
|
||||
self.pub_data_class = pub_data_class
|
||||
|
@ -118,33 +141,45 @@ class TCPROSPub(TCPROSTransportProtocol):
|
|||
base.update(self.headers)
|
||||
return base
|
||||
|
||||
## ROS Protocol handler for TCPROS. Accepts both TCPROS topic
|
||||
## connections as well as ROS service connections over TCP. TCP server
|
||||
## socket is run once start_server() is called -- this is implicitly
|
||||
## called during init_publisher().
|
||||
class TCPROSHandler(rospy.transport.ProtocolHandler):
|
||||
## @param self
|
||||
"""
|
||||
ROS Protocol handler for TCPROS. Accepts both TCPROS topic
|
||||
connections as well as ROS service connections over TCP. TCP server
|
||||
socket is run once start_server() is called -- this is implicitly
|
||||
called during init_publisher().
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
"""ctor"""
|
||||
self.tcp_nodelay_map = {} # { topic : tcp_nodelay}
|
||||
|
||||
## @param tcp_nodelay bool: If True, sets TCP_NODELAY on
|
||||
## publisher's socket (disables Nagle algorithm). This results
|
||||
## in lower latency publishing at the cost of efficiency.
|
||||
def set_tcp_nodelay(self, topic, tcp_nodelay):
|
||||
"""
|
||||
@param tcp_nodelay: If True, sets TCP_NODELAY on publisher's
|
||||
socket (disables Nagle algorithm). This results in lower
|
||||
latency publishing at the cost of efficiency.
|
||||
@type tcp_nodelay: bool
|
||||
"""
|
||||
self.tcp_nodelay_map[rospy.names.resolve_name(topic)] = tcp_nodelay
|
||||
|
||||
## stops the TCP/IP server responsible for receiving inbound connections
|
||||
## @param self
|
||||
def shutdown(self):
|
||||
"""
|
||||
stops the TCP/IP server responsible for receiving inbound connections
|
||||
"""
|
||||
pass
|
||||
|
||||
## Connect to topic \a topic_name on Publisher \a pub_uri using TCPROS.
|
||||
## @param self
|
||||
## @param topic_name str: topic name
|
||||
## @param pub_uri str: XML-RPC URI of publisher
|
||||
## @param protocol_params [XmlRpcLegal]: protocol parameters to use for connecting
|
||||
## @return int, str, int: code, message, debug
|
||||
def create_transport(self, topic_name, pub_uri, protocol_params):
|
||||
"""
|
||||
Connect to topic topic_name on Publisher pub_uri using TCPROS.
|
||||
@param topic_name str: topic name
|
||||
@type topic_name: str
|
||||
@param pub_uri: XML-RPC URI of publisher
|
||||
@type pub_uri: str
|
||||
@param protocol_params: protocol parameters to use for connecting
|
||||
@type protocol_params: [XmlRpcLegal]
|
||||
@return: code, message, debug
|
||||
@rtype: (int, str, int)
|
||||
"""
|
||||
|
||||
#Validate protocol params = [TCPROS, address, port]
|
||||
if type(protocol_params) != list or len(protocol_params) != 3:
|
||||
|
@ -175,38 +210,53 @@ class TCPROSHandler(rospy.transport.ProtocolHandler):
|
|||
conn.close()
|
||||
return 0, "ERROR: Race condition failure: duplicate topic subscriber [%s] was created"%(topic_name), 0
|
||||
|
||||
## @param self
|
||||
## @param protocol str: name of protocol
|
||||
## @return bool: True if protocol is supported
|
||||
def supports(self, protocol):
|
||||
"""
|
||||
@param protocol: name of protocol
|
||||
@type protocol: str
|
||||
@return: True if protocol is supported
|
||||
@rtype: bool
|
||||
"""
|
||||
return protocol == TCPROS
|
||||
|
||||
## @param self
|
||||
def get_supported(self):
|
||||
"""
|
||||
Get supported protocols
|
||||
"""
|
||||
return [[TCPROS]]
|
||||
|
||||
## Initialize this node to receive an inbound TCP connection,
|
||||
## i.e. startup a TCP server if one is not already running.
|
||||
## @param self
|
||||
## @param topic_name str
|
||||
## @param protocol [str, value*]: negotiated protocol
|
||||
## parameters. protocol[0] must be the string 'TCPROS'
|
||||
## @return (int, str, list): (code, msg, [TCPROS, addr, port])
|
||||
def init_publisher(self, topic_name, protocol):
|
||||
def init_publisher(self, topic_name, protocol):
|
||||
"""
|
||||
Initialize this node to receive an inbound TCP connection,
|
||||
i.e. startup a TCP server if one is not already running.
|
||||
@param topic_name: topic name
|
||||
@type topic_name: str
|
||||
@param protocol: negotiated protocol
|
||||
parameters. protocol[0] must be the string 'TCPROS'
|
||||
@type protocol: [str, value*]
|
||||
@return: (code, msg, [TCPROS, addr, port])
|
||||
@rtype: (int, str, list)
|
||||
"""
|
||||
if protocol[0] != TCPROS:
|
||||
return 0, "Internal error: protocol does not match TCPROS: %s"%protocol, []
|
||||
start_tcpros_server()
|
||||
addr, port = get_tcpros_server_address()
|
||||
return 1, "ready on %s:%s"%(addr, port), [TCPROS, addr, port]
|
||||
|
||||
## Process incoming topic connection. Reads in topic name from
|
||||
## handshake and creates the appropriate TCPROSPub handler for the
|
||||
## connection.
|
||||
## @param sock socket: socket connection
|
||||
## @param client_addr (str, int): client address
|
||||
## @param header dict: key/value pairs from handshake header
|
||||
## @return str: error string or None
|
||||
def topic_connection_handler(self, sock, client_addr, header):
|
||||
"""
|
||||
Process incoming topic connection. Reads in topic name from
|
||||
handshake and creates the appropriate L{TCPROSPub} handler for the
|
||||
connection.
|
||||
@param sock: socket connection
|
||||
@type sock: socket.socket
|
||||
@param client_addr: client address
|
||||
@type client_addr: (str, int)
|
||||
@param header: key/value pairs from handshake header
|
||||
@type header: dict
|
||||
@return: error string or None
|
||||
@rtype: str
|
||||
"""
|
||||
for required in ['topic', 'md5sum', 'callerid']:
|
||||
if not required in header:
|
||||
return "Missing required '%s' field"%required
|
||||
|
|
|
@ -32,6 +32,8 @@
|
|||
#
|
||||
# Revision $Id: service.py 2945 2008-11-26 03:48:27Z sfkwc $
|
||||
|
||||
"""Internal use: Service-specific extensions for TCPROS support"""
|
||||
|
||||
import cStringIO
|
||||
import socket
|
||||
import struct
|
||||
|
@ -92,8 +94,10 @@ def service_connection_handler(sock, client_addr, header):
|
|||
thread.start_new_thread(service.handle, (transport, header))
|
||||
|
||||
|
||||
## Protocol implementation for Services over TCPROS
|
||||
class TCPService(TCPROSTransportProtocol):
|
||||
"""
|
||||
Protocol implementation for Services over TCPROS
|
||||
"""
|
||||
|
||||
## ctor.
|
||||
## @param self
|
||||
|
@ -110,24 +114,30 @@ class TCPService(TCPROSTransportProtocol):
|
|||
return {'service': self.name, 'type': self.service_class._type,
|
||||
'md5sum': self.service_class._md5sum, 'callerid': rospy.names.get_caller_id() }
|
||||
|
||||
## Protocol Implementation for Service clients over TCPROS
|
||||
class TCPROSServiceClient(TCPROSTransportProtocol):
|
||||
|
||||
## ctor.
|
||||
## @param self
|
||||
## @param name str: name of service
|
||||
## @param service_class Service: Service data type class
|
||||
## @param headers dict: identifier for Service session
|
||||
## @param buff_size int: size of buffer (bytes) for reading responses from Service.
|
||||
"""Protocol Implementation for Service clients over TCPROS"""
|
||||
|
||||
def __init__(self, name, service_class, headers=None, buff_size=DEFAULT_BUFF_SIZE):
|
||||
"""
|
||||
ctor.
|
||||
@param name: name of service
|
||||
@type name: str
|
||||
@param service_class: Service data type class
|
||||
@type service_class: Service
|
||||
@param headers: identifier for Service session
|
||||
@type headers: dict
|
||||
@param buff_size: size of buffer (bytes) for reading responses from Service.
|
||||
@type buff_size: int
|
||||
"""
|
||||
super(TCPROSServiceClient, self).__init__(name, service_class._response_class)
|
||||
self.service_class = service_class
|
||||
self.headers = headers or {}
|
||||
self.buff_size = buff_size
|
||||
|
||||
## TCPROSTransportProtocol API
|
||||
## @param self
|
||||
def get_header_fields(self):
|
||||
"""
|
||||
TCPROSTransportProtocol API
|
||||
"""
|
||||
headers = {'service': self.name, 'md5sum': self.service_class._md5sum,
|
||||
'callerid': rospy.names.get_caller_id()}
|
||||
# The current implementation allows user-supplied headers to
|
||||
|
@ -137,12 +147,15 @@ class TCPROSServiceClient(TCPROSTransportProtocol):
|
|||
headers[k] = v
|
||||
return headers
|
||||
|
||||
## utility for reading the OK-byte/error-message header preceding each message
|
||||
## @param self
|
||||
## @param sock: socket connection. Will be read from if OK byte is
|
||||
## false and error message needs to be read
|
||||
## @param b StringIO: buffer to read from
|
||||
def _read_ok_byte(self, b, sock):
|
||||
"""
|
||||
Utility for reading the OK-byte/error-message header preceding each message.
|
||||
@param sock: socket connection. Will be read from if OK byte is
|
||||
false and error message needs to be read
|
||||
@type sock: socket.socket
|
||||
@param b: buffer to read from
|
||||
@type b: StringIO
|
||||
"""
|
||||
if b.tell() == 0:
|
||||
return
|
||||
pos = b.tell()
|
||||
|
@ -153,9 +166,18 @@ class TCPROSServiceClient(TCPROSTransportProtocol):
|
|||
str = self._read_service_error(sock, b)
|
||||
raise ServiceException("service [%s] responded with an error: %s"%(self.name, str))
|
||||
|
||||
## In service implementation, reads in OK byte that preceeds each response. The OK byte allows
|
||||
## for the passing of error messages instead of a response message
|
||||
def read_messages(self, b, msg_queue, sock):
|
||||
"""
|
||||
In service implementation, reads in OK byte that preceeds each
|
||||
response. The OK byte allows for the passing of error messages
|
||||
instead of a response message
|
||||
@param b: buffer
|
||||
@type b: StringIO
|
||||
@param msg_queue: Message queue to append to
|
||||
@type msg_queue: [Message]
|
||||
@param sock: socket to read from
|
||||
@type sock: socket.socket
|
||||
"""
|
||||
self._read_ok_byte(b, sock)
|
||||
rospy.msg.deserialize_messages(b, msg_queue, self.recv_data_class, queue_size=self.queue_size, max_msgs=1, start=1) #rospy.msg
|
||||
#deserialize_messages only resets the buffer to the start
|
||||
|
@ -194,16 +216,16 @@ class ServiceProxy(_Service):
|
|||
"""
|
||||
ctor.
|
||||
@param name: name of service to call
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param service_class: auto-generated service class
|
||||
@type service_class: Service class
|
||||
@type service_class: Service class
|
||||
@param persistent: if True, proxy maintains a persistent
|
||||
connection to service. While this results in better call
|
||||
performance, persistent connections are discouraged as they are
|
||||
less resistent to network issues and service restarts.
|
||||
@type persistent: bool
|
||||
@type persistent: bool
|
||||
@param headers: arbitrary headers
|
||||
@type headers: dict
|
||||
@type headers: dict
|
||||
"""
|
||||
super(ServiceProxy, self).__init__(name, service_class)
|
||||
self.uri = None
|
||||
|
@ -234,9 +256,9 @@ class ServiceProxy(_Service):
|
|||
"""
|
||||
private routine for getting URI of service to call
|
||||
@param request: request message
|
||||
@type request: Message
|
||||
@type request: Message
|
||||
@param timeout: timeout in seconds
|
||||
@type timeout: float
|
||||
@type timeout: float
|
||||
"""
|
||||
if not isinstance(request, rospy.msg.Message):
|
||||
raise TypeError("request object is not a valid request message instance")
|
||||
|
@ -268,9 +290,9 @@ class ServiceProxy(_Service):
|
|||
"""
|
||||
Call the service
|
||||
@param request: service request message instance
|
||||
@type request: Messsage
|
||||
@type request: Messsage
|
||||
@param timeout: (keyword arg) number of seconds before request times out
|
||||
@type timeout: float
|
||||
@type timeout: float
|
||||
@raise TypeError: if request is not of the valid type (Message)
|
||||
@raise ServiceException: if communication with remote service fails
|
||||
@raise ROSSerializationException: If unable to serialize
|
||||
|
@ -328,15 +350,15 @@ class Service(_Service):
|
|||
"""
|
||||
ctor.
|
||||
@param name: service name
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param service_class: ServiceDefinition class
|
||||
@type service_class: ServiceDefinition class
|
||||
@type service_class: ServiceDefinition class
|
||||
@param handler: callback function for processing service
|
||||
request. Function takes in a ServiceRequest and returns a
|
||||
ServiceResponse of the appropriate type.
|
||||
@type handler: fn(req)->resp
|
||||
@type handler: fn(req)->resp
|
||||
@param buff_size: size of buffer for reading incoming requests. Should be at least size of request message
|
||||
@type buff_size: int
|
||||
@type buff_size: int
|
||||
"""
|
||||
super(Service, self).__init__(name, service_class)
|
||||
self.handler = handler
|
||||
|
@ -362,7 +384,7 @@ class Service(_Service):
|
|||
"""
|
||||
Stop this service
|
||||
@param reason: human-readable shutdown reason
|
||||
@type reason: str
|
||||
@type reason: str
|
||||
"""
|
||||
self.done = True
|
||||
logdebug('[%s].shutdown: reason [%s]'%(self.name, reason))
|
||||
|
@ -387,9 +409,9 @@ class Service(_Service):
|
|||
"""
|
||||
Send error message to client
|
||||
@param transport: transport connection to client
|
||||
@type transport: Transport
|
||||
@type transport: Transport
|
||||
@param err_msg: error message to send to client
|
||||
@type err_msg: str
|
||||
@type err_msg: str
|
||||
"""
|
||||
transport.write_data(struct.pack('<BI%ss'%len(err_msg), 0, len(err_msg), err_msg))
|
||||
|
||||
|
@ -397,7 +419,7 @@ class Service(_Service):
|
|||
"""
|
||||
Process a single incoming request.
|
||||
@param transport: transport instance
|
||||
@type transport: L{TCPROSTransport}
|
||||
@type transport: L{TCPROSTransport}
|
||||
@param request: Message
|
||||
"""
|
||||
try:
|
||||
|
@ -422,9 +444,9 @@ class Service(_Service):
|
|||
own thread. If header['persistent'] is set to 1, method will
|
||||
block until connection is broken.
|
||||
@param transport: transport instance
|
||||
@type transport: L{TCPROSTransport}
|
||||
@type transport: L{TCPROSTransport}
|
||||
@param header: headers from client
|
||||
@type header: dict
|
||||
@type header: dict
|
||||
"""
|
||||
if 'persistent' in header and \
|
||||
header['persistent'].lower() in ['1', 'true']:
|
||||
|
|
|
@ -32,12 +32,16 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
## Adapted from http://aspn.activestate.com/ASPN/Cookbook/Python/Recipe/203871
|
||||
##
|
||||
## Added a 'marker' to tasks so that multiple tasks with the same
|
||||
## marker are not executed. As we are using the thread pool for i/o
|
||||
## tasks, the marker is set to the i/o name. This prevents a slow i/o
|
||||
## for gobbling up all of our threads
|
||||
"""
|
||||
Internal threadpool library for zenmaster.
|
||||
|
||||
Adapted from U{http://aspn.activestate.com/ASPN/Cookbook/Python/Recipe/203871}
|
||||
|
||||
Added a 'marker' to tasks so that multiple tasks with the same
|
||||
marker are not executed. As we are using the thread pool for i/o
|
||||
tasks, the marker is set to the i/o name. This prevents a slow i/o
|
||||
for gobbling up all of our threads
|
||||
"""
|
||||
|
||||
import threading, logging, traceback
|
||||
from time import sleep
|
||||
|
|
|
@ -32,13 +32,13 @@
|
|||
#
|
||||
# Revision $Id$
|
||||
|
||||
"""rospy implementation of topics.
|
||||
"""
|
||||
rospy implementation of topics.
|
||||
|
||||
Client API
|
||||
==========
|
||||
|
||||
L{Publisher} and L{Subscriber} are the client-API facing instantiation
|
||||
of topics.
|
||||
L{Publisher} and L{Subscriber} are the client API for topics.
|
||||
|
||||
Internal Implementation
|
||||
=======================
|
||||
|
@ -54,20 +54,13 @@ L{_TopicManager}
|
|||
The L{_TopicManager} does the backend topic bookkeeping for the local
|
||||
node. Use L{get_topic_manager()} to access singleton. Actual topic
|
||||
implementations are done through the
|
||||
L{_TopicImpl}/L{_PublisherImpl}/L{_SubscriberImpl}
|
||||
hierarchy. Client code generates instances of type
|
||||
L{Publisher}/L{Subscriber}, which enable to client to create
|
||||
multiple publishers/subscribers of that topic that get controlled
|
||||
access to the underlying share connections.
|
||||
L{_TopicImpl}/L{_PublisherImpl}/L{_SubscriberImpl} hierarchy. Client
|
||||
code generates instances of type L{Publisher}/L{Subscriber}, which
|
||||
enable to client to create multiple publishers/subscribers of that
|
||||
topic that get controlled access to the underlying share connections.
|
||||
|
||||
Common parent classes for all rospy topics. The rospy topic autogenerators
|
||||
create classes that are children of these implementations.
|
||||
|
||||
TopicListener
|
||||
=============
|
||||
|
||||
Subscribe to new topics created by the local node. This is mainly
|
||||
a hook for creating registration calls to the master.
|
||||
"""
|
||||
|
||||
from __future__ import with_statement
|
||||
|
@ -92,15 +85,20 @@ logger = logging.getLogger('rospy.topics')
|
|||
# for interfacing with topics, while _TopicImpl implements the
|
||||
# underlying connection details.
|
||||
|
||||
##Base class of client API topic references
|
||||
class Topic(object):
|
||||
"""Base class of L{Publisher} and L{Subscriber}"""
|
||||
|
||||
## @param self
|
||||
## @param name str: graph resource name of topic, e.g. 'laser'.
|
||||
## @param data_class Message: message class for serialization
|
||||
## @param reg_type Registration.PUB or Registration.SUB
|
||||
## @raise ValueError if parameters are invalid
|
||||
def __init__(self, name, data_class, reg_type):
|
||||
"""
|
||||
@param name: graph resource name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@param data_class: message class for serialization
|
||||
@type data_class: Message
|
||||
@param reg_type Registration.PUB or Registration.SUB
|
||||
@type reg_type: str
|
||||
@raise ValueError: if parameters are invalid
|
||||
"""
|
||||
|
||||
if not name or not isinstance(name, basestring):
|
||||
raise ValueError("topic parameter 'name' is not a non-empty string")
|
||||
if data_class is None:
|
||||
|
@ -117,29 +115,39 @@ class Topic(object):
|
|||
self.reg_type = reg_type
|
||||
self.impl = get_topic_manager().acquire_impl(reg_type, self.name, data_class)
|
||||
|
||||
## get the number of connections to other ROS nodes for this topic. For a Publisher,
|
||||
## this corresponds to the number of nodes subscribing. For a Subscriber, the number
|
||||
## of publishers.
|
||||
def get_num_connections(self):
|
||||
"""
|
||||
get the number of connections to other ROS nodes for this topic. For a Publisher,
|
||||
this corresponds to the number of nodes subscribing. For a Subscriber, the number
|
||||
of publishers.
|
||||
@return: number of connections
|
||||
@rtype: int
|
||||
"""
|
||||
return self.impl.get_num_connections()
|
||||
|
||||
## unpublish/unsubscribe from topic. Topic instance is no longer
|
||||
## valid after this call.
|
||||
## @param self
|
||||
def unregister(self):
|
||||
"""
|
||||
unpublish/unsubscribe from topic. Topic instance is no longer
|
||||
valid after this call.
|
||||
"""
|
||||
get_topic_manager().release_impl(self.reg_type, self.name)
|
||||
self.impl = self.name = self.type = self.md5sum = self.data_class = None
|
||||
|
||||
## Base class of internal topic implementations. Each topic has a
|
||||
## singleton _TopicImpl implementation for managing the underlying
|
||||
## connections.
|
||||
class _TopicImpl(object):
|
||||
"""
|
||||
Base class of internal topic implementations. Each topic has a
|
||||
singleton _TopicImpl implementation for managing the underlying
|
||||
connections.
|
||||
"""
|
||||
|
||||
## Base constructor
|
||||
## @param self
|
||||
## @param name str: graph resource name of topic, e.g. 'laser'.
|
||||
## @param data_class Message: message data class
|
||||
def __init__(self, name, data_class):
|
||||
"""
|
||||
Base constructor
|
||||
@param name: graph resource name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@param data_class Message: message data class
|
||||
@type data_class: Message
|
||||
"""
|
||||
self.name = resolve_name(name) #NOTE: remapping occurs here!
|
||||
self.data_class = data_class
|
||||
self.type = data_class._type
|
||||
|
@ -160,9 +168,8 @@ class _TopicImpl(object):
|
|||
#STATS
|
||||
self.dead_connections = [] #for retaining stats on old conns
|
||||
|
||||
## close I/O
|
||||
## @param self
|
||||
def close(self):
|
||||
"""close I/O"""
|
||||
self.closed = True
|
||||
with self.c_lock:
|
||||
for c in self.connections:
|
||||
|
@ -177,11 +184,13 @@ class _TopicImpl(object):
|
|||
with self.c_lock:
|
||||
return len(self.connections)
|
||||
|
||||
## Query whether or not a connection with the associated \a
|
||||
## endpoint has been added to this object.
|
||||
## @param self
|
||||
## @param endpoint_id str: endpoint ID associated with connection.
|
||||
def has_connection(self, endpoint_id):
|
||||
"""
|
||||
Query whether or not a connection with the associated \a
|
||||
endpoint has been added to this object.
|
||||
@param endpoint_id: endpoint ID associated with connection.
|
||||
@type endpoint_id: str
|
||||
"""
|
||||
# save reference to avoid lock
|
||||
conn = self.connections
|
||||
for c in conn:
|
||||
|
@ -189,18 +198,24 @@ class _TopicImpl(object):
|
|||
return True
|
||||
return False
|
||||
|
||||
## Check to see if this topic is connected to other publishers/subscribers
|
||||
## @param self
|
||||
def has_connections(self):
|
||||
"""
|
||||
Check to see if this topic is connected to other publishers/subscribers
|
||||
@return: True if topic is connected
|
||||
@rtype: bool
|
||||
"""
|
||||
if self.connections:
|
||||
return True
|
||||
return False
|
||||
|
||||
## Add a connection to this topic.
|
||||
## @param self
|
||||
## @param c Transport: connection instance
|
||||
## @return bool: True if connection was added
|
||||
def add_connection(self, c):
|
||||
"""
|
||||
Add a connection to this topic.
|
||||
@param c: connection instance
|
||||
@type c: Transport
|
||||
@return: True if connection was added
|
||||
@rtype: bool
|
||||
"""
|
||||
with self.c_lock:
|
||||
# c_lock is to make add_connection thread-safe, but we
|
||||
# still make a copy of self.connections so that the rest of the
|
||||
|
@ -214,10 +229,12 @@ class _TopicImpl(object):
|
|||
|
||||
return True
|
||||
|
||||
## Remove connection from topic.
|
||||
## @param self
|
||||
## @param c Transport: connection instance to remove
|
||||
def remove_connection(self, c):
|
||||
"""
|
||||
Remove connection from topic.
|
||||
@param c: connection instance to remove
|
||||
@type c: Transport
|
||||
"""
|
||||
try:
|
||||
# c_lock is to make remove_connection thread-safe, but we
|
||||
# still make a copy of self.connections so that the rest of the
|
||||
|
@ -233,20 +250,21 @@ class _TopicImpl(object):
|
|||
finally:
|
||||
self.c_lock.release()
|
||||
|
||||
## Get the stats for this topic
|
||||
## @param self
|
||||
## @return list: stats for topic in getBusInfo() format
|
||||
## ((connection_id, destination_caller_id, direction, transport, topic_name, connected)*)
|
||||
def get_stats_info(self): # STATS
|
||||
"""
|
||||
Get the stats for this topic
|
||||
@return: stats for topic in getBusInfo() format::
|
||||
((connection_id, destination_caller_id, direction, transport, topic_name, connected)*)
|
||||
@rtype: list
|
||||
"""
|
||||
# save referenceto avoid locking
|
||||
connections = self.connections
|
||||
dead_connections = self.dead_connections
|
||||
return [(c.id, c.endpoint_id, c.direction, c.transport_type, self.name, True) for c in connections] + \
|
||||
[(c.id, c.endpoint_id, c.direction, c.transport_type, self.name, False) for c in dead_connections]
|
||||
|
||||
## Get the stats for this topic (API stub)
|
||||
## @param self
|
||||
def get_stats(self): # STATS
|
||||
"""Get the stats for this topic (API stub)"""
|
||||
raise Exception("subclasses must override")
|
||||
|
||||
# Implementation note: Subscriber attaches to a _SubscriberImpl
|
||||
|
@ -271,20 +289,20 @@ class Subscriber(Topic):
|
|||
these parameters differently.
|
||||
|
||||
@param name: graph resource name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_class: data type class to use for messages,
|
||||
e.g. std_msgs.msg.String
|
||||
@type data_class: Message class
|
||||
@type data_class: Message class
|
||||
@param callback: function to call ( fn(data)) when data is
|
||||
received. If callback_args is set, the function must accept
|
||||
the callback_args as a second argument, i.e. fn(data,
|
||||
callback_args). NOTE: Additional callbacks can be added using
|
||||
add_callback().
|
||||
@type callback: str
|
||||
@type callback: str
|
||||
@param callback_args: additional arguments to pass to the
|
||||
callback. This is useful when you wish to reuse the same
|
||||
callback for multiple subscriptions.
|
||||
@type callback_args: any
|
||||
@type callback_args: any
|
||||
@param queue_size: maximum number of messages to receive at
|
||||
a time. This will generally be 1 or None (infinite,
|
||||
default). buff_size should be increased if this parameter
|
||||
|
@ -292,19 +310,19 @@ class Subscriber(Topic):
|
|||
buffer before being discarded. Setting queue_size
|
||||
buff_size to a non-default value affects all subscribers to
|
||||
this topic in this process.
|
||||
@type queue_size: int
|
||||
@type queue_size: int
|
||||
@param buff_size: incoming message buffer size in bytes. If
|
||||
queue_size is set, this should be set to a number greater
|
||||
than the queue_size times the average message size. Setting
|
||||
buff_size to a non-default value affects all subscribers to
|
||||
this topic in this process.
|
||||
@type buff_size: int
|
||||
@type buff_size: int
|
||||
@param tcp_nodelay: if True, request TCP_NODELAY from
|
||||
publisher. Use of this option is not generally recommended
|
||||
in most cases as it is better to rely on timestamps in
|
||||
message data. Setting tcp_nodelay to True enables TCP_NODELAY
|
||||
for all subscribers in the same python process.
|
||||
@type tcp_nodelay: bool
|
||||
@type tcp_nodelay: bool
|
||||
@raise ROSException: if parameters are invalid
|
||||
"""
|
||||
super(Subscriber, self).__init__(name, data_class, Registration.SUB)
|
||||
|
@ -322,16 +340,19 @@ class Subscriber(Topic):
|
|||
if tcp_nodelay:
|
||||
self.impl.set_tcp_nodelay(tcp_nodelay)
|
||||
|
||||
## _Topic*Impl classes manage the underlying connections for a given topic. The
|
||||
# separation of the _Topic*Impl classes and the Topic* classes that a client
|
||||
# instantiates allows the client to generate multiple Topic* instances for a given
|
||||
# topic. It also hides the underlying API for managing the connections.
|
||||
class _SubscriberImpl(_TopicImpl):
|
||||
"""
|
||||
Underyling L{_TopicImpl} implementation for subscriptions.
|
||||
"""
|
||||
|
||||
## @param self
|
||||
## @param name str: graph resource name of topic, e.g. 'laser'.
|
||||
# @param data_class Message: Message data class
|
||||
def __init__(self, name, data_class):
|
||||
"""
|
||||
ctor.
|
||||
@param name: graph resource name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@param data_class: Message data class
|
||||
@type data_class: Message
|
||||
"""
|
||||
super(_SubscriberImpl, self).__init__(name, data_class)
|
||||
# client-methods to invoke on new messages. should only modify
|
||||
# under lock. This is a list of 2-tuples (fn, args), where
|
||||
|
@ -341,17 +362,22 @@ class _SubscriberImpl(_TopicImpl):
|
|||
self.buff_size = DEFAULT_BUFF_SIZE
|
||||
self.tcp_nodelay = False
|
||||
|
||||
## Set the value of TCP_NODELAY, which causes the Nagle algorithm
|
||||
## to be disabled for future topic connections, if the publisher
|
||||
## supports it.
|
||||
def set_tcp_nodelay(self, tcp_nodelay):
|
||||
"""
|
||||
Set the value of TCP_NODELAY, which causes the Nagle algorithm
|
||||
to be disabled for future topic connections, if the publisher
|
||||
supports it.
|
||||
"""
|
||||
self.tcp_nodelay = tcp_nodelay
|
||||
|
||||
## Set the receive queue size. If more than queue_size messages are waiting to be deserialized,
|
||||
## they are discarded.
|
||||
## @param self
|
||||
## @param queue_size int: incoming queue size. Must be positive integer or None.
|
||||
def set_queue_size(self, queue_size):
|
||||
"""
|
||||
Set the receive queue size. If more than queue_size messages
|
||||
are waiting to be deserialized, they are discarded.
|
||||
|
||||
@param queue_size int: incoming queue size. Must be positive integer or None.
|
||||
@type queue_size: int
|
||||
"""
|
||||
if queue_size == -1:
|
||||
self.queue_size = None
|
||||
elif queue_size == 0:
|
||||
|
@ -361,22 +387,28 @@ class _SubscriberImpl(_TopicImpl):
|
|||
else:
|
||||
self.queue_size = queue_size
|
||||
|
||||
## Set the receive buffer size. The exact meaning of this is
|
||||
## transport dependent.
|
||||
## @param self
|
||||
## @param buff_size int: receive buffer size
|
||||
def set_buff_size(self, buff_size):
|
||||
"""
|
||||
Set the receive buffer size. The exact meaning of this is
|
||||
transport dependent.
|
||||
@param buff_size: receive buffer size
|
||||
@type buff_size: int
|
||||
"""
|
||||
if type(buff_size) != int:
|
||||
raise ROSException("buffer size must be an integer")
|
||||
elif buff_size <= 0:
|
||||
raise ROSException("buffer size must be a positive integer")
|
||||
self.buff_size = buff_size
|
||||
|
||||
## Get the stats for this topic subscriber
|
||||
## @param self
|
||||
## @return list: stats for topic in getBusStats() publisher format (topicName, connStats),
|
||||
## where connStats = [connectionId, bytesReceived, numSent, dropEstimate, connected]*
|
||||
def get_stats(self): # STATS
|
||||
"""
|
||||
Get the stats for this topic subscriber
|
||||
@return: stats for topic in getBusStats() publisher format::
|
||||
(topicName, connStats)
|
||||
where connStats is::
|
||||
[connectionId, bytesReceived, numSent, dropEstimate, connected]*
|
||||
@rtype: list
|
||||
"""
|
||||
# save reference to avoid locking
|
||||
conn = self.connections
|
||||
dead_conn = self.dead_connections
|
||||
|
@ -386,13 +418,16 @@ class _SubscriberImpl(_TopicImpl):
|
|||
for c in chain(conn, dead_conn)] )
|
||||
return stats
|
||||
|
||||
## Register a callback to be invoked whenever a new message is received
|
||||
## @param self
|
||||
## @param cb fn(msg): callback function to invoke with message data
|
||||
## instance, i.e. fn(data). If callback args is set, they will be passed
|
||||
## in as the second argument.
|
||||
## @param cb_cargs Any: additional arguments to pass to callback
|
||||
def add_callback(self, cb, cb_args):
|
||||
"""
|
||||
Register a callback to be invoked whenever a new message is received
|
||||
@param cb: callback function to invoke with message data
|
||||
instance, i.e. fn(data). If callback args is set, they will
|
||||
be passed in as the second argument.
|
||||
@type cb: fn(msg)
|
||||
@param cb_cargs: additional arguments to pass to callback
|
||||
@type cb_cargs: Any
|
||||
"""
|
||||
with self.c_lock:
|
||||
# we lock in order to serialize calls to add_callback, but
|
||||
# we copy self.callbacks so we can it
|
||||
|
@ -400,10 +435,12 @@ class _SubscriberImpl(_TopicImpl):
|
|||
new_callbacks.append((cb, cb_args))
|
||||
self.callbacks = new_callbacks
|
||||
|
||||
## Called by underlying connection transport for each new message received
|
||||
## @param self
|
||||
## @param msgs [Message]: message data
|
||||
def receive_callback(self, msgs):
|
||||
"""
|
||||
Called by underlying connection transport for each new message received
|
||||
@param msgs: message data
|
||||
@type msgs: [Message]
|
||||
"""
|
||||
# save reference to avoid lock
|
||||
callbacks = self.callbacks
|
||||
for msg in msgs:
|
||||
|
@ -429,13 +466,13 @@ class SubscribeListener(object):
|
|||
"""
|
||||
callback when a peer has subscribed from a topic
|
||||
@param topic_name: topic name. NOTE: topic name will be resolved/remapped
|
||||
@type topic_name: str
|
||||
@type topic_name: str
|
||||
@param topic_publish: method to publish message data to all subscribers
|
||||
@type topic_publish: fn(data)
|
||||
@type topic_publish: fn(data)
|
||||
@param peer_publish: method to publish message data to
|
||||
new subscriber. NOTE: behavior for the latter is
|
||||
transport-dependent as some transports may be broadcast only.
|
||||
@type peer_publish: fn(data)
|
||||
@type peer_publish: fn(data)
|
||||
"""
|
||||
pass
|
||||
|
||||
|
@ -443,9 +480,9 @@ class SubscribeListener(object):
|
|||
"""
|
||||
callback when a peer has unsubscribed from a topic
|
||||
@param topic_name: topic name. NOTE: topic name will be resolved/remapped
|
||||
@type topic_name: str
|
||||
@type topic_name: str
|
||||
@param num_peers: number of remaining peers subscribed to topic
|
||||
@type num_peers: int
|
||||
@type num_peers: int
|
||||
"""
|
||||
pass
|
||||
|
||||
|
@ -464,20 +501,20 @@ class Publisher(Topic):
|
|||
"""
|
||||
Constructor
|
||||
@param name: resource name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_class: message class for serialization
|
||||
@type data_class: Message class
|
||||
@type data_class: Message class
|
||||
@param subscriber_listener: listener for
|
||||
subscription events. May be None.
|
||||
@type subscriber_listener: L{SubscribeListener}
|
||||
@type subscriber_listener: L{SubscribeListener}
|
||||
@param tcp_nodelay: If True, sets TCP_NODELAY on
|
||||
publisher's socket (disables Nagle algorithm). This results
|
||||
in lower latency publishing at the cost of efficiency.
|
||||
@type tcp_nodelay: bool
|
||||
@type tcp_nodelay: bool
|
||||
@param latch: If True, the last message published is
|
||||
'latched', meaning that any future subscribers will be sent
|
||||
that message immediately upon connection.
|
||||
@type latch: bool
|
||||
@type latch: bool
|
||||
@raise ROSException: if parameters are invalid
|
||||
"""
|
||||
super(Publisher, self).__init__(name, data_class, Registration.PUB)
|
||||
|
@ -535,18 +572,15 @@ def args_kwds_to_message(data_class, args, kwds):
|
|||
|
||||
class _PublisherImpl(_TopicImpl):
|
||||
"""
|
||||
_PublisherImpl classes manage the underlying connections for a given topic. The
|
||||
separation of the _PublisherImpl classes and the L{Publisher} class that a client
|
||||
instantiates allows the client to generate multiple L{Publisher} instances for a given
|
||||
topic. It also hides the underlying API for managing the connections.
|
||||
Underyling L{_TopicImpl} implementation for publishers.
|
||||
"""
|
||||
|
||||
def __init__(self, name, data_class):
|
||||
"""
|
||||
@param name: name of topic, e.g. 'laser'.
|
||||
@type name: str
|
||||
@type name: str
|
||||
@param data_class: Message data class
|
||||
@type data_class: Message
|
||||
@type data_class: Message
|
||||
"""
|
||||
super(_PublisherImpl, self).__init__(name, data_class)
|
||||
self.buff = cStringIO.StringIO()
|
||||
|
@ -568,7 +602,7 @@ class _PublisherImpl(_TopicImpl):
|
|||
Add connection headers to this Topic for future connections.
|
||||
@param headers: key/values will be added to current connection
|
||||
header set, overriding any existing keys if they conflict.
|
||||
@type headers: dict
|
||||
@type headers: dict
|
||||
"""
|
||||
self.headers.update(headers)
|
||||
|
||||
|
@ -598,7 +632,7 @@ class _PublisherImpl(_TopicImpl):
|
|||
"""
|
||||
Add a L{SubscribeListener} for subscribe events.
|
||||
@param l: listener instance
|
||||
@type l: L{SubscribeListener}
|
||||
@type l: L{SubscribeListener}
|
||||
"""
|
||||
self.subscriber_listeners.append(l)
|
||||
|
||||
|
@ -616,7 +650,7 @@ class _PublisherImpl(_TopicImpl):
|
|||
the latch is enabled, c will be sent a the value of the
|
||||
latch.
|
||||
@param c: connection instance
|
||||
@type c: L{Transport}
|
||||
@type c: L{Transport}
|
||||
@return: True if connection was added
|
||||
@rtype: bool
|
||||
"""
|
||||
|
@ -634,7 +668,7 @@ class _PublisherImpl(_TopicImpl):
|
|||
"""
|
||||
Remove existing connection from this topic.
|
||||
@param c: connection instance to remove
|
||||
@type c: L{Transport}
|
||||
@type c: L{Transport}
|
||||
"""
|
||||
super(_PublisherImpl, self).remove_connection(c)
|
||||
num = len(self.connections)
|
||||
|
@ -649,9 +683,9 @@ class _PublisherImpl(_TopicImpl):
|
|||
ensure proper message publish ordering.
|
||||
|
||||
@param message: message data instance to publish
|
||||
@type message: L{Message}
|
||||
@type message: L{Message}
|
||||
@param connection_override: publish to this connection instead of all
|
||||
@type connection_override: L{Transport}
|
||||
@type connection_override: L{Transport}
|
||||
@return: True if the data was published, False otherwise.
|
||||
@rtype: bool
|
||||
@raise roslib.message.SerializationError: if Message instance is unable to serialize itself
|
||||
|
@ -763,11 +797,11 @@ class _TopicManager(object):
|
|||
"""
|
||||
Add L{_TopicImpl} instance to map
|
||||
@param ps: a pub/sub impl instance
|
||||
@type ps: L{_TopicImpl}
|
||||
@type ps: L{_TopicImpl}
|
||||
@param map: { topic: _TopicImpl} map to record instance in
|
||||
@type map: dict
|
||||
@type map: dict
|
||||
@param reg_type: L{rospy.registration.Registration.PUB} or L{rospy.registration.Registration.SUB}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
topic = ps.name
|
||||
logger.debug("tm._add: %s, %s, %s", topic, ps.type, reg_type)
|
||||
|
@ -791,11 +825,11 @@ class _TopicManager(object):
|
|||
"""
|
||||
Remove L{_TopicImpl} instance from map
|
||||
@param ps: a pub/sub impl instance
|
||||
@type ps: L{_TopicImpl}
|
||||
@type ps: L{_TopicImpl}
|
||||
@param map: topic->_TopicImpl map to remove instance in
|
||||
@type map: dict
|
||||
@type map: dict
|
||||
@param reg_type: L{rospy.registration.Registration.PUB} or L{rospy.registration.Registration.SUB}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
topic = ps.name
|
||||
logger.debug("tm._remove: %s, %s, %s", topic, ps.type, reg_type)
|
||||
|
@ -816,9 +850,9 @@ class _TopicManager(object):
|
|||
testing purposes. Unlike acquire_impl, it does not alter the
|
||||
ref count.
|
||||
@param topic: Topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param reg_type: L{rospy.registration.Registration.PUB} or L{rospy.registration.Registration.SUB}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
if reg_type == Registration.PUB:
|
||||
map = self.pubs
|
||||
|
@ -837,11 +871,11 @@ class _TopicManager(object):
|
|||
topic implementation marks that another Topic instance is
|
||||
using the TopicImpl.
|
||||
@param topic: Topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param reg_type: L{rospy.registration.Registration.PUB} or L{rospy.registration.Registration.SUB}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
@param data_class: message class for topic
|
||||
@type data_class: Message Class
|
||||
@type data_class: Message Class
|
||||
"""
|
||||
if reg_type == Registration.PUB:
|
||||
map = self.pubs
|
||||
|
@ -873,9 +907,9 @@ class _TopicManager(object):
|
|||
TopicImpl.
|
||||
|
||||
@param topic: Topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@param reg_type: L{rospy.registration.Registration.PUB} or L{rospy.registration.Registration.SUB}
|
||||
@type reg_type: str
|
||||
@type reg_type: str
|
||||
"""
|
||||
if reg_type == Registration.PUB:
|
||||
map = self.pubs
|
||||
|
@ -898,7 +932,7 @@ class _TopicManager(object):
|
|||
def get_publisher_impl(self, topic):
|
||||
"""
|
||||
@param topic: topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@return: list of L{_PublisherImpl}s
|
||||
@rtype: [L{_PublisherImpl}]
|
||||
"""
|
||||
|
@ -907,7 +941,7 @@ class _TopicManager(object):
|
|||
def get_subscriber_impl(self, topic):
|
||||
"""
|
||||
@param topic: topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@return: subscriber for the specified topic.
|
||||
@rtype: L{_SubscriberImpl}
|
||||
"""
|
||||
|
@ -916,7 +950,7 @@ class _TopicManager(object):
|
|||
def has_subscription(self, topic):
|
||||
"""
|
||||
@param topic: topic name
|
||||
@type topic: str
|
||||
@type topic: str
|
||||
@return: True if manager has subscription for specified topic
|
||||
@rtype: bool
|
||||
"""
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
# Copyright (c) 2008, Willow Garage, Inc.
|
||||
# Revision $Id$
|
||||
|
||||
"""Command-line handler for ROS zenmaster (Python Master)"""
|
||||
|
||||
import getopt
|
||||
import logging
|
||||
import os
|
||||
|
@ -42,8 +44,6 @@ import time
|
|||
|
||||
import rospy
|
||||
|
||||
"""Command-line handler for ROS zenmaster (Python Master)"""
|
||||
|
||||
# Environment variables used to configure master/slave
|
||||
|
||||
from roslib.rosenv import ROS_ROOT, ROS_MASTER_URI, ROS_HOSTNAME, ROS_NAMESPACE, ROS_PACKAGE_PATH, ROS_LOG_DIR
|
||||
|
|
Loading…
Reference in New Issue