Class: Topic

Topic

new Topic(options)

Publish and/or subscribe to a topic in ROS. Emits the following events: * 'warning' - if there are any warning during the Topic creation * 'message' - the message data from rosbridge
Parameters:
Name Type Description
options object with following keys: * ros - the ROSLIB.Ros connection handle * name - the topic name, like /cmd_vel * messageType - the message type, like 'std_msgs/String' * compression - the type of compression to use, like 'png' * throttle_rate - the rate (in ms in between messages) at which to throttle the topics * queue_size - the queue created at bridge side for re-publishing webtopics (defaults to 100) * latch - latch the topic when publishing * queue_length - the queue length at bridge side used when subscribing (defaults to 0, no queueing).
Source:

Methods

Registers as a publisher for the topic.
Source:

publish(message)

Publish the message.
Parameters:
Name Type Description
message A ROSLIB.Message object.
Source:

subscribe(callback)

Every time a message is published for the given topic, the callback will be called with the message object.
Parameters:
Name Type Description
callback function with the following params: * message - the published message
Source:

toStream()

Publish a connected ROS topic to a duplex stream. This stream can be piped to, which will publish to the topic
Source:

unadvertise()

Unregisters as a publisher for the topic.
Source:

unsubscribe(callback)

Unregisters as a subscriber for the topic. Unsubscribing stop remove all subscribe callbacks. To remove a call back, you must explicitly pass the callback function in.
Parameters:
Name Type Description
callback the optional callback to unregister, if * provided and other listeners are registered the topic won't * unsubscribe, just stop emitting to the passed listener
Source: