rosbag has both C++ and Python APIs for reading messages from and writing messages to bag files.

See the rosbag Cookbook for useful code snippets using the APIs.

Note that the rosbag API's are not thread-safe for reading and writing any given bag file. Users of the APIs must ensure no concurrent input/output operations are performed on different threads.


The rosbag C++ API works on the premise of creating "views" of one or more bags using "queries". A Query is an abstract class which defines a function that filters whether or not the messages from a connection are to be included. This function has access to topic_name, datatype, md5sum, message definition as well as the connection header. Additionally, each Query can specify a start and end time for the range of times it includes.

Multiple queries can be added to a View, including queries from different bags. The View then provides an iterator interface across the bags, sorted based on time.

For more information, see the C++ Code API.

Example usage for write:

   1     #include <rosbag/bag.h>
   2     #include <std_msgs/Int32.h>
   3     #include <std_msgs/String.h>
   5     rosbag::Bag bag;
   6"test.bag", rosbag::bagmode::Write);
   8     std_msgs::String str;
   9 = std::string("foo");
  11     std_msgs::Int32 i;
  12 = 42;
  14     bag.write("chatter", ros::Time::now(), str);
  15     bag.write("numbers", ros::Time::now(), i);
  17     bag.close();

Example usage for read:

   1     #include <rosbag/bag.h>
   2     #include <rosbag/view.h>
   3     #include <std_msgs/Int32.h>
   4     #include <std_msgs/String.h>
   6     #include <boost/foreach.hpp>
   7     #define foreach BOOST_FOREACH
   9     rosbag::Bag bag;
  10"test.bag", rosbag::bagmode::Read);
  12     std::vector<std::string> topics;
  13     topics.push_back(std::string("chatter"));
  14     topics.push_back(std::string("numbers"));
  16     rosbag::View view(bag, rosbag::TopicQuery(topics));
  18     foreach(rosbag::MessageInstance const m, view)
  19     {
  20         std_msgs::String::ConstPtr s = m.instantiate<std_msgs::String>();
  21         if (s != NULL)
  22             std::cout << s->data << std::endl;
  24         std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
  25         if (i != NULL)
  26             std::cout << i->data << std::endl;
  27     }
  29     bag.close();

Python API

The Python API is similar, except the the "query" is specified as optional arguments to the read_messages function, which returns the "view" as a generator.

For more information, see Python Code API

Example usage for write:

   1 import rosbag
   2 from std_msgs.msg import Int32, String
   4 bag = rosbag.Bag('test.bag', 'w')
   6 try:
   7     str = String()
   8 = 'foo'
  10     i = Int32()
  11 = 42
  13     bag.write('chatter', str)
  14     bag.write('numbers', i)
  15 finally:
  16     bag.close()

Example usage for read:

   1 import rosbag
   2 bag = rosbag.Bag('test.bag')
   3 for topic, msg, t in bag.read_messages(topics=['chatter', 'numbers']):
   4     print msg
   5 bag.close()

In line 4, the loop prints all the data that consists of:

  • topic: the topic of the message

  • msg: the message

  • t: time of message. The time is represented as a rospy Time object (t.secs, t.nsecs)

See the rosbag Cookbook for useful code snippets using the APIs.

Wiki: rosbag/Code API (last edited 2017-08-01 10:50:58 by GvdHoorn)