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

rospy.msg.AnyMsg How do we use?

asked 2015-02-08 21:04:11 -0500

new2ros gravatar image

Hi,

First time poster here, I'm just wondering how does one use an implementation of this. I am reading some code and from what I can tell the programmer hasn't collected any information of the data just the size of it to determine the bandwidth.

Source: https://code.google.com/p/wu-robotics...

if one knows the topic and message type could one reconstruct the message? does anyone have an example of this, or a good reference?

Thanks Michael

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
6

answered 2015-02-09 03:42:32 -0500

updated 2015-02-09 03:47:56 -0500

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:

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().

edit flag offensive delete link more

Comments

Thanks for the response I'm still pretty new at this, I have been able to get this working on my test program, Thanks. So does that mean rospy.msg.AnyMsg should only be used to calculate bandwidth? Is there any other purpose for it?

new2ros gravatar image new2ros  ( 2015-02-09 19:04:24 -0500 )edit

I've never used it, so I can't think of other use cases right now. It gives you access to the raw serialized data, which might come in handy sometimes (let's say if you write your own rosbag implementation and just want to store the data away without having to look at it).

Martin Günther gravatar image Martin Günther  ( 2015-02-10 04:09:34 -0500 )edit
3

answered 2018-03-23 09:01:36 -0500

lucasw gravatar image

updated 2019-10-06 09:47:58 -0500

Here is a small example from @wkentaro that receives a messages, sleeps a certain amount and also adds that amount to the header stamp, then republishes it on a new topic https://gist.github.com/wkentaro/2cd5...

from roslib.message import get_message_class
from rospy.msg import AnyMsg
...
        self._sub = rospy.Subscriber('~input', AnyMsg, self._cb)

    def _cb(self, anymsg):
        topic_types = self._master.getTopicTypes()
        msg_name = [ty for tp, ty in topic_types if tp == self._sub.name][0]
        msg_class = get_message_class(msg_name)
        msg = msg_class().deserialize(anymsg._buff)

I think this could also work:

msg_name = topic._connection_header['type']

But what if there is no header? This could guard against that:

if 'Header header' in anymsg._connection_header['message_definition']

I used it in a subscriber bootstrapping technique where an AnyMsg is subscribed to, then there is a check to see if the message has a header, then that first subscriber is unsubscribed and a second subscriber that is of the proper type is created (but I didn't give much example code) #q230676

In other cases I've used it to subscribe to topics where a warning is generated if the topic hasn't published recently, the AnyMsg prevents deserialization overhead and I can subscribe to any number of different types of topics using the same code. That is similar to the bandwidth calculation.

(One thing to note is that rospy doesn't like two concurrent subscribers in the same node on the same topic with different types- if one is AnyMsg and the other is the full topic type- the message is delivered to both callbacks as an AnyMsg, https://github.com/ros/ros_comm/issue...)

http://docs.ros.org/kinetic/api/rospy...

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-02-08 21:04:11 -0500

Seen: 3,482 times

Last updated: Oct 06 '19