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.
C++ API
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>
4
5 rosbag::Bag bag;
6 bag.open("test.bag", rosbag::bagmode::Write);
7
8 std_msgs::String str;
9 str.data = std::string("foo");
10
11 std_msgs::Int32 i;
12 i.data = 42;
13
14 bag.write("chatter", ros::Time::now(), str);
15 bag.write("numbers", ros::Time::now(), i);
16
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>
5
6 #include <boost/foreach.hpp>
7 #define foreach BOOST_FOREACH
8
9 rosbag::Bag bag;
10 bag.open("test.bag", rosbag::bagmode::Read);
11
12 std::vector<std::string> topics;
13 topics.push_back(std::string("chatter"));
14 topics.push_back(std::string("numbers"));
15
16 rosbag::View view(bag, rosbag::TopicQuery(topics));
17
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;
23
24 std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
25 if (i != NULL)
26 std::cout << i->data << std::endl;
27 }
28
29 bag.close();
Another C++ example, using C++11:
1 #include <rosbag/bag.h>
2 #include <rosbag/view.h>
3 #include <std_msgs/Int32.h>
4
5 rosbag::Bag bag;
6 bag.open("test.bag"); // BagMode is Read by default
7
8 for(rosbag::MessageInstance const m: rosbag::View(bag))
9 {
10 std_msgs::Int32::ConstPtr i = m.instantiate<std_msgs::Int32>();
11 if (i != nullptr)
12 std::cout << i->data << std::endl;
13 }
14
15 bag.close();
Python API
The Python API is similar, except that 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:
Example usage for read:
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.
Using bagpy to decode rosbag files
bagpy provides a wrapper class bagreader written in python that provides an easy to use interface for reading bag files recorded by rosbag record command. This wrapper class uses ROS's python API rosbag internally to perform all operations.
Example usage for decoding bagfile:
1 import bagpy
2 from bagpy import bagreader
3 import pandas as pd
4
5 b = bagreader('test.bag')
6
7 # replace the topic name as per your need
8 LASER_MSG = b.message_by_topic('/vehicle/front_laser_points')
9 LASER_MSG
10 df_laser = pd.read_csv(LASER_MSG)
11 df_laser # prints laser data in the form of pandas dataframe
Link to the bagpy repository: https://github.com/jmscslgroup/bagpy
See this post for an extended tutorial.