Note: This tutorial assumes that you have completed the previous tutorials: Recording and playing back data. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Reading messages from a bag file
Description: Learn two ways to read messages from desired topics in a bag file, including using the ros_readbagfile script.Keywords: data, rosbag, extract, play, info, bag, messages, readbagfile, ros_readbagfile
Tutorial Level: BEGINNER
Next Tutorial: Getting started with roswtf
Contents
- See Also:
- Download or record a bag file
- Option 1: play back the messages immediately and look at the output in multiple terminals
- Option 2: use the ros_readbagfile script to easily extract the topics of interest
- Why use `ros_readbagfile` for this purpose instead of `rostopic echo -b`?
- Next Tutorial:
See Also:
Other rosbag tutorials here: rosbag/Tutorials.
Note: This tutorial assumes that you have completed the previous tutorials: Recording and playing back data. |
Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Reading messages from a bag file
Description: Learn two ways to read messages from desired topics in a bag file, including using the really handy ros_readbagfile script.Keywords: data, rosbag, extract, play, info, bag, messages, readbagfile, ros_readbagfile
Tutorial Level: BEGINNER
Next Tutorial: Producing filtered bag files
Contents
Download or record a bag file
First, you need a bag file. Produce your own by following this tutorial (ROS/Tutorials/Recording and playing back data).
Assuming you are on a system with ROS already running, here is a quick command to record a 30 second snippet of data into a bag file for just topics you are interested in, ex: /topic1, /topic2, and /topic3. Since we are setting a duration of 30 seconds, the recording will automatically stop after this time:
rosbag record --duration=30 --output-name=/tmp/mybagfile.bag \ /topic1 /topic2 /topic3
---
The rest of this tutorial will be done assuming you've downloaded the webviz.io demo bag file using the wget command as shown above. You will go through two options to read/extract messages from the bag file.
Note that in any of the commands below, the time command is prepended simply because it will print out how long each command takes, and since sometimes these commands can take a long time, it is useful to use the time command to gain an idea of how long a given command should take. If you don't want to use it, you may remove the time part of any of the commands below.
Option 1: play back the messages immediately and look at the output in multiple terminals
Source: this material was adapted from instructions first published in this document here.
You need to know the exact topic names you'd like to read from the bag file. So, let's see what's in the bag file. In any terminal, manually inspect all published topics and how many messages were published to each topic with this command:
time rosbag info demo.bag # OR (if you know part of the topic names of interest before-hand): time rosbag info mybag.bag | grep -E "(topic1|topic2|topic3)"
Sample output:$ time rosbag info demo.bag path: demo.bag version: 2.0 duration: 20.0s start: Mar 21 2017 19:37:58.00 (1490150278.00) end: Mar 21 2017 19:38:17.00 (1490150298.00) size: 696.2 MB messages: 5390 compression: none [600/600 chunks] types: bond/Status [eacc84bf5d65b6777d4c50f463dfb9c8] diagnostic_msgs/DiagnosticArray [60810da900de1dd6ddd437c3503511da] diagnostic_msgs/DiagnosticStatus [d0ce08bc6e5ba34c7754f563a9cabaf1] nav_msgs/Odometry [cd5e73d190d741a2f92e81eda573aca7] radar_driver/RadarTracks [6a2de2f790cb8bb0e149d45d297462f8] sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743] sensor_msgs/NavSatFix [2d3a8cd499b9b4a0249fb98fd05cfa48] sensor_msgs/PointCloud2 [1158d486dd51d683ce2f1be655c3c181] sensor_msgs/Range [c005c34273dc426c67a020a87bc24148] sensor_msgs/TimeReference [fded64a0265108ba86c3d38fb11c0c16] tf2_msgs/TFMessage [94810edda583a504dfda3829e70d7eec] velodyne_msgs/VelodyneScan [50804fc9533a0e579e6322c04ae70566] topics: /diagnostics 140 msgs : diagnostic_msgs/DiagnosticArray /diagnostics_agg 40 msgs : diagnostic_msgs/DiagnosticArray /diagnostics_toplevel_state 40 msgs : diagnostic_msgs/DiagnosticStatus /gps/fix 146 msgs : sensor_msgs/NavSatFix /gps/rtkfix 200 msgs : nav_msgs/Odometry /gps/time 192 msgs : sensor_msgs/TimeReference /image_raw 600 msgs : sensor_msgs/Image /obs1/gps/fix 30 msgs : sensor_msgs/NavSatFix /obs1/gps/rtkfix 200 msgs : nav_msgs/Odometry /obs1/gps/time 136 msgs : sensor_msgs/TimeReference /radar/points 400 msgs : sensor_msgs/PointCloud2 /radar/range 400 msgs : sensor_msgs/Range /radar/tracks 400 msgs : radar_driver/RadarTracks /tf 1986 msgs : tf2_msgs/TFMessage /velodyne_nodelet_manager/bond 80 msgs : bond/Status /velodyne_packets 200 msgs : velodyne_msgs/VelodyneScan /velodyne_points 200 msgs : sensor_msgs/PointCloud2 real 0m1.003s user 0m0.620s sys 0m0.283s
Notice that there are 30 messages published on topic /obs1/gps/fix, and 40 on topic /diagnostics_agg. Let's just extract those.
- In terminal 1 (this terminal, for example), start up a ros core, which runs the required ROS master node:
roscore
Open up another terminal. Note: to open up another terminal tab in the same terminal window you can use Ctrl + Shift + T on Ubuntu. Subscribe to the /obs1/gps/fix topic, echoing (printing) everything published on this topic, while also teeing it to a file for later review, all in yaml format:
rostopic echo /obs1/gps/fix | tee topic1.yaml
You'll see:$ rostopic echo /obs1/gps/fix | tee topic1.yaml WARNING: topic [/obs1/gps/fix] does not appear to be published yet
Open up another terminal. Subscribe to the other topic: /diagnostics_agg.
rostopic echo /diagnostics_agg | tee topic2.yaml
You'll see:$ rostopic echo /diagnostics_agg | tee topic2.yaml WARNING: topic [/diagnostics_agg] does not appear to be published yet
- Repeat this process for as many topics as you like. Each topic must have its own terminal.
Open up another terminal to play the bag file. We will now play back the bag file as quickly as possible (using the --immediate option), publishing ONLY the topics of interest. The format is:
time rosbag play --immediate demo.bag --topics /topic1 /topic2 /topic3 /topicN
So in our case, the command would be:time rosbag play --immediate demo.bag --topics /obs1/gps/fix /diagnostics_agg
You'll see:$ time rosbag play --immediate demo.bag --topics /obs1/gps/fix /diagnostics_agg [ INFO] [1591916465.758724557]: Opening demo.bag Waiting 0.2 seconds after advertising topics... done. Hit space to toggle paused, or 's' to step. [RUNNING] Bag Time: 1490150297.770734 Duration: 19.703405 / 19.703405 Done. real 0m1.570s user 0m0.663s sys 0m0.394s
Done! Now go look at your two terminals which were each subsribed to a topic, and you'll see the output of all messages for each topic type, in YAML format, with a --- line between each message. Use a text editor of your choice, preferably with Syntax Highlighting for YAML file types (ex: Sublime Text 3) to view the messages in the files. The last two messages in topic1.yaml, for instance, look like this:
--- header: seq: 4027 stamp: secs: 1490150296 nsecs: 66947432 frame_id: "gps" status: status: 0 service: 1 latitude: 37.4008017844 longitude: -122.108119889 altitude: -6.4380177824 position_covariance: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] position_covariance_type: 0 --- header: seq: 4028 stamp: secs: 1490150297 nsecs: 744347249 frame_id: "gps" status: status: 0 service: 1 latitude: 37.4007565466 longitude: -122.108159482 altitude: -6.35130467023 position_covariance: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] position_covariance_type: 0 ---
If for some reason one of your rostopic processes missed the messages, just kill its process with Ctrl + C, restart it, and call the rosbag play command again.
Option 2: use the ros_readbagfile script to easily extract the topics of interest
Source: this material was adapted from instructions first published in this document here, and the Python script is from here: ros_readbag.py.
Note: you can kill any running processes. No roscore, for instance, is required.
Download and install `ros_readbag.py` using these commands. Be sure to read the comments in the top of the file for the latest information on installation instructions and python dependencies.
# Download the file wget https://raw.githubusercontent.com/ElectricRCAircraftGuy/eRCaGuy_dotfiles/master/useful_scripts/ros_readbagfile.py # Make it executable chmod +x ros_readbagfile.py # Ensure you have the ~/bin directory for personal binaries mkdir -p ~/bin # Move this executable script into that directory as `ros_readbagfile`, so that it will # be available as that command mv ros_readbagfile.py ~/bin/ros_readbagfile # Re-source your ~/.profile file to ensure ~/bin is in your PATH, so you can use this # new `ros_readbagfile` command you just installed # Note: this assumes you are on Linux Ubuntu with a default `~/.profile` file. If you're # on some other Linux distribution, such as Arch Linux, you can manually create the # `~/.profile` file. See here for details: # https://answers.ros.org/question/371583/ros_readbagfile-command-not-found/?answer=403354#post-id-403354 . ~/.profile # # Install python dependencies (see the comments at the top of the ros_readbagfile.py # file for the latest dependencies and instructions) pip install bagpy pip3 install bagpy
Note: if your terminal still says it cannot find the command when trying to run it, you may need to ensure ~/bin is part of your PATH variable. See my answer here for details.
Determine the exact topic names you'd like to read from the bag file, by using rosbag info, as shown in Step 1 of Option 1 above.
Now use ros_readbagfile. The general format is:
# read these topics and print them to stdout time ros_readbagfile <mybagfile.bag> [topic1] [topic2] [topic3] [...] # Write to the topics.yaml file withOUT also printing to stdout time ros_readbagfile <mybagfile.bag> [topic1] [topic2] [topic3] [...] > topics.yaml # OR (preferred, so you can easily see it is still running): write to the # topics.yaml file AND print to stdout time ros_readbagfile <mybagfile.bag> [topic1] [topic2] [topic3] [...] | tee topics.yaml
To read the same messages shown in Option 1 above, use:# (preferred, so you can easily see it is still running): write to the # topics.yaml file AND print to stdout time ros_readbagfile demo.bag /obs1/gps/fix /diagnostics_agg | tee topics.yaml
Optionally, to see "progress" by watching the yaml file grow in size, in a new terminal, run the following. Note: the yaml text file will be about 2x as large as the original binary .bag file when complete.watch -n 1 'du -sk topics.yaml | awk '\''{printf "%.3f MiB %s\n", $1/1024, $2}'\'''
That's it! You'll see it print out all 70 messages quickly. Here is what the last little bit of the terminal output looks like:key: "Early diagnostic update count:" value: "0" - key: "Zero seen diagnostic update count:" value: "0" # ======================================= # topic: /obs1/gps/fix # msg_count: 30 # timestamp (sec): 1490150297.770734310 # - - - header: seq: 4028 stamp: secs: 1490150297 nsecs: 744347249 frame_id: "gps" status: status: 0 service: 1 latitude: 37.40075654660259 longitude: -122.10815948235131 altitude: -6.351304670230949 position_covariance: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] position_covariance_type: 0 # ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ # Total messages found: 70 # # /diagnostics_agg: 40 # /obs1/gps/fix: 30 # # DONE. # ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ real 0m0.812s user 0m0.599s sys 0m0.077s
Now view topics.yaml with your preferred text editor or viewer (ex: Sublime Text 4, gedit, emacs, vim, less, etc) to see all of the messages it extracted from the bag file.
Note that topics.yaml is a true YAML-formatted file. All non-YAML content, such as message separators, is commented out with the # symbol.
More .yaml file analysis
Now that you have the .yaml file (produced from the .bag file), here are some demonstrations of how to scan it for a list of keys or text strings you are interested in to see if certain data is present.
Note that the following examples require the ripgrep (rg) command, which is like grep only waaay faster. See here: https://github.com/BurntSushi/ripgrep#installation. Install ripgrep (rg) with:
Let's say you want to find a list of all key entries which begin with "piksi_". You can do so by searching for the string "key: "piksi_", as follows. The rg 'key: "piksi_' topics.yaml part searches the "topics.yaml" text file for the 'key: "piksi_' string, the sort -V part sorts all of the output lines, and the awk '!seen[$0]++' part removes duplicate entries, so that you only see one line of each match. Command and output:
Let's search for all key data entries which begin with "GPS", "Duration", or "Minimum". "OR" type regular expression searches take the general format: (str1|str2|str3|etc), with | being read as "or" in this case. So, searching for "GPS", "Duration", or "Minimum" can be done with the following regular expression search string: '(key: "GPS|key: "Duration|key: "Minimum)'. Here is the command to run: ...and here is the full output:
Answer: Because rostopic is extremley slow! This command, running on a fast computer (4-core/8-thread Pentium i7 w/m.2 SSD), for instance, takes 11.5 minutes to read an 18 GB bag file! The ros_readbagfile script, however, takes only 1 min 37 sec on the same computer to read the same topic from the same 18 GB bag file! Therefore, ros_readbagfile is 11.5/(1+37/60) = ~7x faster! Because rostopic can only read 1 single topic at a time, whereas ros_readbagfile can read any number of topics at once! END. sudo apt update && sudo apt install ripgrep
Example 1:
time rg 'key: "piksi_' topics.yaml | sort -V | awk '!seen[$0]++'
$ time rg 'key: "piksi_' topics.yaml | sort -V | awk '!seen[$0]++'
key: "piksi_llh_diag: Frequency Status"
key: "piksi_rtk_diag: Frequency Status"
key: "piksi_rtk_diag: Piksi Status"
key: "piksi_time_diag: Frequency Status"
real 0m0.009s
user 0m0.003s
sys 0m0.011s
Example 2:
time rg '(key: "GPS|key: "Duration|key: "Minimum)' topics.yaml | sort -V | awk '!seen[$0]++'
$ time rg '(key: "GPS|key: "Duration|key: "Minimum)' topics.yaml | sort -V | awk '!seen[$0]++'
key: "Duration of window (s)"
key: "GPS RTK height difference (m)"
key: "GPS RTK horizontal accuracy (m)"
key: "GPS RTK meters east"
key: "GPS RTK meters north"
key: "GPS RTK orientation east"
key: "GPS RTK orientation north"
key: "GPS RTK orientation up"
key: "GPS RTK solution status (4 = good)"
key: "GPS RTK velocity east"
key: "GPS RTK velocity flags"
key: "GPS RTK velocity north"
key: "GPS RTK velocity up"
key: "GPS altitude"
key: "GPS latitude"
key: "GPS lat/lon horizontal accuracy (m)"
key: "GPS lat/lon solution status"
key: "GPS longitude"
key: "Minimum acceptable frequency (Hz)"
real 0m0.023s
user 0m0.023s
sys 0m0.008s
Why use `ros_readbagfile` for this purpose instead of `rostopic echo -b`?
time rostopic echo -b large_bag_file.bag /topic1
time ros_readbagfile large_bag_file.bag /topic1
ros_readbagfile <mybagfile.bag> [topic1] [topic2] [topic3] [...] [topic1000]
Next Tutorial:
Now that you've learned how to read messages from a pre-recorded bag file, let's learn how to troubleshoot with roswtf.