ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

Why would you want to use AnyMsg if you know the topic name and topic type? In that case, you could use a simple subscriber.

But even if you don't know topic name and type beforehand, you can subscribe to any topic and get the deserialized messages. I've written a small script to demonstrate this:

import rospy
import rostopic
import rosgraph

rospy.init_node('mynode')

topics = [t for t, _ in rosgraph.Master('/mynode').getPublishedTopics('') if not t.startswith('/rosout')]

for t in topics:
    msg_class, _, _ = rostopic.get_topic_class(t)
    msg = rospy.wait_for_message(t, msg_class)
    print "\n\n================================================================================"
    print "received a message on topic %s:" % t
    print msg

The script simply gets one message from each published topic and prints it. The msg object is a fully deserialized message, so you can do anything with it; for example, if the message has a header field, you can access it via msg.header. If you're interested in all messages from a topic (instead of just a single one), simply use a rospy.Subscriber instead of rospy.wait_for_message().

Why would you want to use AnyMsg if you know the topic name and topic type? In that case, you could use a simple subscriber.subscriber:

import rospy
from sensor_msgs.msg import Imu

def cb(msg):
    print msg

rospy.init_node('mynode')
rospy.Subscriber('/imu', Imu, cb)
rospy.spin()

But even if you don't know topic name and type beforehand, you can subscribe to any topic and get the deserialized messages. I've written a small script to demonstrate this:

import rospy
import rostopic
import rosgraph

rospy.init_node('mynode')

topics = [t for t, _ in rosgraph.Master('/mynode').getPublishedTopics('') if not t.startswith('/rosout')]

for t in topics:
    msg_class, _, _ = rostopic.get_topic_class(t)
    msg = rospy.wait_for_message(t, msg_class)
    print "\n\n================================================================================"
    print "received a message on topic %s:" % t
    print msg

The script simply gets one message from each published topic and prints it. The msg object is a fully deserialized message, so you can do anything with it; for example, if the message has a header field, you can access it via msg.header. If you're interested in all messages from a topic (instead of just a single one), simply use a rospy.Subscriber instead of rospy.wait_for_message().