This page contains a collection of code fragments demonstrating use of the rosbag APIs.
Contents
Python
Rewrite bag with header timestamps
To replace message timestamps in a bag with header timestamps:
1 import rosbag
2
3 with rosbag.Bag('output.bag', 'w') as outbag:
4 for topic, msg, t in rosbag.Bag('input.bag').read_messages():
5 # This also replaces tf timestamps under the assumption
6 # that all transforms in the message share the same timestamp
7 if topic == "/tf" and msg.transforms:
8 outbag.write(topic, msg, msg.transforms[0].header.stamp)
9 else:
10 outbag.write(topic, msg, msg.header.stamp if msg._has_header else t)
This is useful in the case that the message receipt time substantially differs from the generation time, e.g. when messages are recorded over an unreliable or slow connection.
Note that this could potentially change the order in which messages are republished by rosbag play.
Add metadata to a bag
To add metadata as the first message in an existing bag:
Get summary information about a bag
To get information about a bag (as returned by rosbag info) as a Python object:
C++
Analyzing Stereo Camera Data
Stereo camera data is stored on four separate topics: image topics for each camera sensor_msgs/Image, and camera info topics for each camera sensor_msgs/CameraInfo. In order to process the data, you need to synchronize messages from all four topics using a message_filters::TimeSynchronizer.
In this example, we're loading the entire bag file to memory before analyzing the images (as opposed to lazy loading).
1 #include <ros/ros.h>
2 #include <rosbag/bag.h>
3 #include <rosbag/view.h>
4
5 #include <boost/foreach.hpp>
6
7 #include <message_filters/subscriber.h>
8 #include <message_filters/time_synchronizer.h>
9
10 #include <sensor_msgs/Image.h>
11 #include <sensor_msgs/CameraInfo.h>
12
13 // A struct to hold the synchronized camera data
14 // Struct to store stereo data
15 class StereoData
16 {
17 public:
18 sensor_msgs::Image::ConstPtr image_l, image_r;
19 sensor_msgs::CameraInfo::ConstPtr cam_info_l, cam_info_r;
20
21 StereoData(const sensor_msgs::Image::ConstPtr &l_img,
22 const sensor_msgs::Image::ConstPtr &r_img,
23 const sensor_msgs::CameraInfo::ConstPtr &l_info,
24 const sensor_msgs::CameraInfo::ConstPtr &r_info) :
25 image_l(l_img),
26 image_r(r_img),
27 cam_info_l(l_info),
28 cam_info_r(r_info)
29 {}
30 };
31
32 /**
33 * Inherits from message_filters::SimpleFilter<M>
34 * to use protected signalMessage function
35 */
36 template <class M>
37 class BagSubscriber : public message_filters::SimpleFilter<M>
38 {
39 public:
40 void newMessage(const boost::shared_ptr<M const> &msg)
41 {
42 signalMessage(msg);
43 }
44 };
45
46 // Callback for synchronized messages
47 void callback(const sensor_msgs::Image::ConstPtr &l_img,
48 const sensor_msgs::Image::ConstPtr &r_img,
49 const sensor_msgs::CameraInfo::ConstPtr &l_info,
50 const sensor_msgs::CameraInfo::ConstPtr &r_info)
51 {
52 StereoData sd(l_img, r_img, l_info, r_info);
53
54 // Stereo dataset is class variable to store data
55 stereo_dataset_.push_back(sd);
56 }
57
58 // Load bag
59 void loadBag(const std::string &filename)
60 {
61 rosbag::Bag bag;
62 bag.open(filename, rosbag::bagmode::Read);
63
64 std::string l_cam = image_ns_ + "/left";
65 std::string r_cam = image_ns_ + "/right";
66 std::string l_cam_image = l_cam + "/image_raw";
67 std::string r_cam_image = r_cam + "/image_raw";
68 std::string l_cam_info = l_cam + "/camera_info";
69 std::string r_cam_info = r_cam + "/camera_info";
70
71 // Image topics to load
72 std::vector<std::string> topics;
73 topics.push_back(l_cam_image);
74 topics.push_back(r_cam_image);
75 topics.push_back(l_cam_info);
76 topics.push_back(r_cam_info);
77
78 rosbag::View view(bag, rosbag::TopicQuery(topics));
79
80 // Set up fake subscribers to capture images
81 BagSubscriber<sensor_msgs::Image> l_img_sub, r_img_sub;
82 BagSubscriber<sensor_msgs::CameraInfo> l_info_sub, r_info_sub;
83
84 // Use time synchronizer to make sure we get properly synchronized images
85 message_filters::TimeSynchronizer<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> sync(l_img_sub, r_img_sub, l_info_sub, r_info_sub, 25);
86 sync.registerCallback(boost::bind(&callback, _1, _2, _3, _4));
87
88 // Load all messages into our stereo dataset
89 BOOST_FOREACH(rosbag::MessageInstance const m, view)
90 {
91 if (m.getTopic() == l_cam_image || ("/" + m.getTopic() == l_cam_image))
92 {
93 sensor_msgs::Image::ConstPtr l_img = m.instantiate<sensor_msgs::Image>();
94 if (l_img != NULL)
95 l_img_sub.newMessage(l_img);
96 }
97
98 if (m.getTopic() == r_cam_image || ("/" + m.getTopic() == r_cam_image))
99 {
100 sensor_msgs::Image::ConstPtr r_img = m.instantiate<sensor_msgs::Image>();
101 if (r_img != NULL)
102 r_img_sub.newMessage(r_img);
103 }
104
105 if (m.getTopic() == l_cam_info || ("/" + m.getTopic() == l_cam_info))
106 {
107 sensor_msgs::CameraInfo::ConstPtr l_info = m.instantiate<sensor_msgs::CameraInfo>();
108 if (l_info != NULL)
109 l_info_sub.newMessage(l_info);
110 }
111
112 if (m.getTopic() == r_cam_info || ("/" + m.getTopic() == r_cam_info))
113 {
114 sensor_msgs::CameraInfo::ConstPtr r_info = m.instantiate<sensor_msgs::CameraInfo>();
115 if (r_info != NULL)
116 r_info_sub.newMessage(r_info);
117 }
118 }
119 bag.close();
120 }






