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

Revision history [back]

click to hide/show revision 1
initial version

I had the same issue and wrote a python script to solve it.

# Print total cumulative serialized msg size per topic
import rosbag
import sys
topic_size_dict = {}
for topic, msg, time in rosbag.Bag(sys.argv[1], 'r').read_messages(raw=True):
  topic_size_dict[topic] = topic_size_dict.get(topic, 0) + len(msg[1])
topic_size = list(topic_size_dict.items())
topic_size.sort(key=lambda x: x[1])
for topic, size in topic_size:
  print(topic, size)

And to explain to simbha why this is useful and needed: I have 102 topics generated by 40+ nodes. Hundreds of thousands of message. I'm not familiar with any of these nodes. But one of them is causing excessive size of bags. As a system administrator/data warehouse guy I want to quickly find out which one exactly so I can contact the responsible developer to fix the issue.

I had the same issue and wrote a python script to solve it.

#!/usr/bin/env python
# Print total cumulative serialized msg size per topic
import rosbag
import sys
topic_size_dict = {}
for topic, msg, time in rosbag.Bag(sys.argv[1], 'r').read_messages(raw=True):
  topic_size_dict[topic] = topic_size_dict.get(topic, 0) + len(msg[1])
topic_size = list(topic_size_dict.items())
topic_size.sort(key=lambda x: x[1])
for topic, size in topic_size:
  print(topic, size)

And to explain to simbha why this is useful and needed: I have 102 topics generated by 40+ nodes. Hundreds of thousands of message. I'm not familiar with any of these nodes. But one of them is causing excessive size of bags. As a system administrator/data warehouse guy I want to quickly find out which one exactly so I can contact the responsible developer to fix the issue.