def __init__(self, name, data_class, subscriber_listener=None, tcp_nodelay=False, latch=False, headers=None): """ Constructor @param name: resource name of topic, e.g. 'laser'. @type name: str @param data_class: message class for serialization @type data_class: L{Message} class @param subscriber_listener: listener for subscription events. May be None. @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 @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 @raise ROSException: if parameters are invalid """ super(Publisher, self).__init__(name, data_class, Registration.PUB) if subscriber_listener: self.impl.add_subscriber_listener(subscriber_listener) if tcp_nodelay: get_tcpros_handler().set_tcp_nodelay(self.resolved_name, tcp_nodelay) if latch: self.impl.enable_latch() if headers: self.impl.add_headers(headers)
def __init__(self, name, data_class, subscriber_listener=None, tcp_nodelay=False, latch=False, headers=None, queue_size=None): """ Constructor @param name: resource name of topic, e.g. 'laser'. @type name: str @param data_class: message class for serialization @type data_class: L{Message} class @param subscriber_listener: listener for subscription events. May be None. @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 @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 @param headers: If not None, a dictionary with additional header key-values being used for future connections. @type headers: dict @param queue_size: The queue size used for asynchronously publishing messages from different threads. A size of zero means an infinite queue, which can be dangerous. When the keyword is not being used or when None is passed all publishing will happen synchronously and a warning message will be printed. @type queue_size: int @raise ROSException: if parameters are invalid """ super(Publisher, self).__init__(name, data_class, Registration.PUB) if subscriber_listener: self.impl.add_subscriber_listener(subscriber_listener) if tcp_nodelay: get_tcpros_handler().set_tcp_nodelay(self.resolved_name, tcp_nodelay) if latch: self.impl.enable_latch() if headers: self.impl.add_headers(headers) if queue_size is not None: self.impl.set_queue_size(queue_size) else: import warnings warnings.warn("The publisher should be created with an explicit keyword argument 'queue_size'. " "Please see http://wiki.ros.org/rospy/Overview/Publishers%20and%20Subscribers for more information.", SyntaxWarning, stacklevel=2)