class Publisher(Topic):
Constructor: Publisher(name, data_class, subscriber_listener, tcp_nodelay, ...)
Class for registering as a publisher of a ROS topic.
Method | __init__ |
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... |
Method | publish |
Publish message data object to this topic. Publish can either be called with the message instance to publish or with the constructor args for a new Message instance, i.e.: |
Inherited from Topic
:
Method | get |
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... |
Method | unregister |
unpublish/unsubscribe from topic. Topic instance is no longer valid after this call. Additional calls to unregister() have no effect. |
Instance Variable | data |
Undocumented |
Instance Variable | impl |
Undocumented |
Instance Variable | md5sum |
Undocumented |
Instance Variable | name |
Undocumented |
Instance Variable | reg |
Undocumented |
Instance Variable | resolved |
Undocumented |
Instance Variable | type |
Undocumented |
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
Publish message data object to this topic. Publish can either be called with the message instance to publish or with the constructor args for a new Message instance, i.e.:
pub.publish(message_instance) pub.publish(message_field_1, message_field_2...) pub.publish(message_field_1='foo', message_field_2='bar')
@param args : L{Message} instance, message arguments, or no args if keyword arguments are used @param kwds : Message keyword arguments. If kwds are used, args must be unset @raise ROSException: If rospy node has not been initialized @raise ROSSerializationException: If unable to serialize message. This is usually a type error with one of the fields.