This page contains a collection of code fragments demonstrating the use of the rosbag APIs.
Contents
Python
Dependencies
rosbag python package uses Cryptodomex and gnupg packages. They can be installed via pip using:
$ pip3 install pycryptodomex python-gnupg
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 to an existing bag:
Note that appending the message with a time stamp earlier than the latest stamp in the bag will affect the duration reported by rosbag info.
Get summary information about a bag
To get information about a bag (as returned by rosbag info) as a Python object:
Or, equivalently:
Get lists of topics and types from a bag
Create a cropped bagfile
For example if you just want the first 100 messages.
Reorder a Bag File Based on Header Timestamps
Rearranges the messages inside a file to ensure they are played back in the order of their timestamps; messages on /tf are played back one second ahead of time to ensure they are available at the time they are referenced.
1 #!/usr/bin/env python
2 import sys
3 import rosbag
4 import time
5 import subprocess
6 import yaml
7 import rospy
8 import os
9 import argparse
10 import math
11 from shutil import move
12
13 try:
14 from yaml import CSafeLoader as Loader
15 except ImportError:
16 from yaml import SafeLoader as Loader
17
18 def status(length, percent):
19 sys.stdout.write('\x1B[2K') # Erase entire current line
20 sys.stdout.write('\x1B[0E') # Move to the beginning of the current line
21 progress = "Progress: ["
22 for i in range(0, length):
23 if i < length * percent:
24 progress += '='
25 else:
26 progress += ' '
27 progress += "] " + str(round(percent * 100.0, 2)) + "%"
28 sys.stdout.write(progress)
29 sys.stdout.flush()
30
31
32 def main(args):
33 parser = argparse.ArgumentParser(description='Reorder a bagfile based on header timestamps.')
34 parser.add_argument('bagfile', nargs=1, help='input bag file')
35 parser.add_argument('--max-offset', nargs=1, help='max time offset (sec) to correct.', default='60', type=float)
36 args = parser.parse_args()
37
38 # Get bag duration
39
40 bagfile = args.bagfile[0]
41
42 output = subprocess.Popen(['rosbag', 'info', '--yaml', bagfile], stdout=subprocess.PIPE).communicate()[0]
43 print(output)
44 info_dict = yaml.load(output, Loader)
45 duration = info_dict['duration']
46 start_time = info_dict['start']
47
48 orig = os.path.splitext(bagfile)[0] + ".orig.bag"
49
50 move(bagfile, orig)
51
52 with rosbag.Bag(bagfile, 'w') as outbag:
53
54 last_time = time.process_time()
55 for topic, msg, t in rosbag.Bag(orig).read_messages():
56
57 if time.process_time() - last_time > .1:
58 percent = (t.to_sec() - start_time) / duration
59 status(40, percent)
60 last_time = time.process_time()
61
62 # This also replaces tf timestamps under the assumption
63 # that all transforms in the message share the same timestamp
64 if topic == "/tf" and msg.transforms:
65 # Writing transforms to bag file 1 second ahead of time to ensure availability
66 diff = math.fabs(msg.transforms[0].header.stamp.to_sec() - t.to_sec())
67 outbag.write(topic, msg, msg.transforms[0].header.stamp - rospy.Duration(1) if diff < args.max_offset else t)
68 elif msg._has_header:
69 diff = math.fabs(msg.header.stamp.to_sec() - t.to_sec())
70 outbag.write(topic, msg, msg.header.stamp if diff < args.max_offset else t)
71 else:
72 outbag.write(topic, msg, t)
73 status(40, 1)
74 print("\ndone")
75
76 if __name__ == "__main__":
77 main(sys.argv[1:])
Export message contents to CSV
This snippet looks through the messages in a bagfile and writes them to a CSV when they meet certain conditions.
1 import sys
2 import os
3 import csv
4 import rosbag
5 import rospy
6
7 ##################
8 # DESCRIPTION:
9 # Creates CSV files of the robot joint states from a rosbag (for visualization with e.g. pybullet)
10 #
11 # USAGE EXAMPLE:
12 # rosrun your_package get_jstate_csvs.py /root/catkin_ws/bagfiles your_bagfile.bag
13 # ##################
14
15 filename = sys.argv[2]
16 directory = sys.argv[1]
17 print("Reading the rosbag file")
18 if not directory.endswith("/"):
19 directory += "/"
20 extension = ""
21 if not filename.endswith(".bag"):
22 extension = ".bag"
23 bag = rosbag.Bag(directory + filename + extension)
24
25 # Create directory with name filename (without extension)
26 results_dir = directory + filename[:-4] + "_results"
27 if not os.path.exists(results_dir):
28 os.makedirs(results_dir)
29
30 print("Writing robot joint state data to CSV")
31
32 with open(results_dir +"/"+filename+'_joint_states.csv', mode='w') as data_file:
33 data_writer = csv.writer(data_file, delimiter=',', quotechar='"', quoting=csv.QUOTE_MINIMAL)
34 data_writer.writerow(['time', 'robot_elbow_joint', 'robot_shoulder_lift_joint',
35 'robot_shoulder_pan_joint', 'robot_wrist_1_joint', 'robot_wrist_2_joint', 'robot_wrist_3_joint'])
36 # Get all message on the /joint states topic
37 for topic, msg, t in bag.read_messages(topics=['/joint_states']):
38 # Only write to CSV if the message is for our robot
39 if msg.name[0] == "robot_elbow_joint":
40 p = msg.position
41 data_writer.writerow([t, p[0], p[1], p[2], p[3], p[4], p[5]])
42
43 print("Finished creating csv file!")
44 bag.close()
C++
Get Rosbag Duration
In this example, we're extracing the full duration of the entire bag in seconds. Since there is no way to directly get this info with the C++ API, we can use the View class like this:
1 #include <rosbag/bag.h>
2 #include <rosbag/view.h>
3
4 int main(int argc, char **argv)
5 {
6 rosbag::Bag bag;
7 bag.open("/path/to/my_bag.bag", rosbag::bagmode::Read);
8
9 rosbag::View view(bag);
10
11 ros::Time bag_begin_time = view.getBeginTime();
12 ros::Time bag_end_time = view.getEndTime();
13
14 std::cout << "ROS bag time: " << (bag_end_time-bag_begin_time).toSec() << "(s)" << std::endl;
15
16 bag.close();
17
18 return 0;
19 }
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 }