Module rostopic

Module rostopic

source code

Classes
  ROSTopicException
Base exception class of rostopic-related errors
  ROSTopicIOException
rostopic errors related to network I/O failures
  ROSTopicHz
ROSTopicHz receives messages for a topic and computes frequency stats
  ROSTopicBandwidth
  CallbackEcho
Callback instance that can print callback data in a variety of formats.
Functions
fn(rospy.Message) -> value
msgevalgen(pattern)
Generates a function that returns the relevant field (aka 'subtopic') of a Message object
source code
str, str, fn
get_topic_type(topic, blocking=False)
Get the topic type.
source code
roslib.message.Message, str, str
get_topic_class(topic, blocking=False)
Get the topic message class
source code
str
get_api(master, caller_id)
Get XML-RPC API of node
source code
 
get_info_text(topic)
Get human-readable topic description
source code
 
create_field_filter(echo_nostr, echo_noarr) source code
[str]
find_by_type(topic_type)
Lookup topics by topic_type
source code
rospy.topics.Publisher, roslib.message.Message class
create_publisher(topic_name, topic_type, latch)
Create rospy.Publisher instance from the string topic name and type.
source code
 
publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=False)
Create new instance of msg_class, populate with pub_args, and publish.
source code
iterator
file_yaml_arg(filename)
Returns: Iterator that yields pub args (list of args)
source code
 
argv_publish(pub, msg_class, pub_args, rate, once, verbose) source code
 
wait_for_subscriber(pub, timeout) source code
 
param_publish_once(pub, msg_class, param_name, verbose) source code
[{str: any}]
param_publish(pub, msg_class, param_name, rate, verbose)
Returns: List of msg dicts in file
source code
 
stdin_publish(pub, msg_class, rate, once, filename, verbose) source code
iterator
stdin_yaml_arg()
Iterate over YAML documents in stdin
source code
 
rostopicmain(argv=None) source code
Variables
  NAME = 'rostopic'
  SUBSCRIBER_TIMEOUT = 5.0
  __package__ = None
Function Details

msgevalgen(pattern)

source code 

Generates a function that returns the relevant field (aka 'subtopic') of a Message object

Parameters:
  • pattern (str) - subtopic, e.g. /x. Must have a leading '/' if specified.
Returns: fn(rospy.Message) -> value
function that converts a message into the desired value

get_topic_type(topic, blocking=False)

source code 

Get the topic type.

Parameters:
  • topic (str) - topic name
  • blocking (bool) - (default False) block until topic becomes available
Returns: str, str, fn
topic type, real topic name and fn to evaluate the message instance if the topic points to a field within a topic, e.g. /rosout/msg. fn is None otherwise.
Raises:

get_topic_class(topic, blocking=False)

source code 

Get the topic message class

Returns: roslib.message.Message, str, str
message class for topic, real topic name, and function for evaluating message objects into the subtopic (or None)
Raises:

get_api(master, caller_id)

source code 

Get XML-RPC API of node

Parameters:
  • master (xmlrpclib.ServerProxy) - XML-RPC handle to ROS Master
  • caller_id (str) - node name
Returns: str
XML-RPC URI of node
Raises:

get_info_text(topic)

source code 

Get human-readable topic description

Parameters:
  • topic (str) - topic name

find_by_type(topic_type)

source code 

Lookup topics by topic_type

Parameters:
  • topic_type (str) - type of topic to find
Returns: [str]
list of topic names that use topic_type

create_publisher(topic_name, topic_type, latch)

source code 

Create rospy.Publisher instance from the string topic name and type. This is a powerful method as it allows creation of rospy.Publisher and Message instances using the topic and type names. This enables more dynamic publishing from Python programs.

Parameters:
  • topic_name (str) - name of topic
  • topic_type (str) - name of topic type
  • latch (bool) - latching topic
Returns: rospy.topics.Publisher, roslib.message.Message class
topic publisher, message class

publish_message(pub, msg_class, pub_args, rate=None, once=False, verbose=False)

source code 

Create new instance of msg_class, populate with pub_args, and publish. This may print output to screen.

Parameters:
  • pub (rospy.Publisher) - Publisher instance for topic
  • msg_class (Class) - Message type
  • pub_args ([val]) - Arguments to initialize message that is published
  • rate (int) - publishing rate (hz) or None for just once
  • once (bool) - publish only once and return
  • verbose (bool) - If True, print more verbose output to stdout

file_yaml_arg(filename)

source code 
Parameters:
  • filename (str) - file name
Returns: iterator
Iterator that yields pub args (list of args)
Raises:

param_publish(pub, msg_class, param_name, rate, verbose)

source code 
Parameters:
  • param_name (str) - ROS parameter name
Returns: [{str: any}]
List of msg dicts in file
Raises:

stdin_publish(pub, msg_class, rate, once, filename, verbose)

source code 
Parameters:
  • filename (str) - name of file to read from instead of stdin, or None

stdin_yaml_arg()

source code 

Iterate over YAML documents in stdin

Returns: iterator
for next list of arguments on stdin. Iterator returns a list of args for each call.