📖
Wiki
Back to my personal website
  • Home
  • Equipment and Devices
    • 3D Printer
    • Laser Cutter
    • Motion Capture System
    • Sensors
      • RGB-D Cameras
      • Velodyne LiDAR
      • Zed Camera
      • RealSense D435i
      • IMU
    • eGPU
    • Nvidia AGX Xavier
    • CPU Benchmark
    • Installation Checklist
  • Development
    • Linux
      • Shell
      • GDB
      • Git
      • Tmux
      • Network
      • Tricks
      • Debug FAQ
    • CMake
      • Catkin Tools
      • CMakeLists
      • CMake Variables
      • CMake Commands
      • CMake: find_package()
    • ROS
      • Gazebo
      • wstool
      • roslaunch
      • rosbag
      • multi-threaded spinner
    • ROS2
      • Convert ROS1 bag to ROS2 bag
    • C++
      • C++ 11
      • C++ Examples
      • C++ Debug
      • Factory Method
      • Timing
    • Google Tools
      • GLog
      • GFlags
      • GTest
      • Style Guide
      • Clang Format
    • PCL
      • Point Type
      • Methods
      • Architecture
      • Code Explained
    • Open3D
      • Python API
      • Registration
      • Visualization
      • Tools
    • OpenCV
      • Documentation
      • Modules
    • Other Libraries
      • Eigen
      • Ceres
      • g2o
      • GTSAM
    • Website
  • Algorithm
    • SLAM
      • K-D Tree
      • Octree
      • Bag of Words
      • Distance Measures
      • Coordinate Systems
      • LOAM
      • Iterative Closest Point
      • Generalized ICP
      • Mahalanobis Distance
    • Computer Science
      • Computational Model
      • Sorting
      • Analysis
      • Complexity Classes (P, NP)
      • Divide and Conquer
      • Greedy Algorithm
      • Dynamic Programming
      • Tree
      • Graph
    • Computer Vision
      • Camera Models
      • Distortion
      • Motion Models
      • Shutter
      • Image Sensors
      • Epipolar Geometry
      • Multiple-View Geometry
    • Datasets
      • RGB-D Datasets
      • Point Cloud Datasets
      • LiDAR SLAM Datasets
  • Math
    • Optimization
      • Convex Optimization
      • Descent Methods
    • Probability
      • Moment
      • Covariance Matrix
      • Stochastic Process
    • Topology
      • References
      • Concepts
      • Topological Spaces
      • Representation of Rotations
      • Representation of 3-sphere
    • Algebra
      • Linear Algebra
      • Matrix Factorization
      • Condition Number
      • Matrix Lie Group
    • Differential Geometry
      • Manifold
      • Submanifold
      • Quotient Manifolds
      • Tangent Space
  • Quadrotor
    • PX4 Development
    • Companion Computer
    • Drone Hardware
    • Propeller Lock
    • Debug
  • Favorites
    • Bookmarks
Powered by GitBook
On this page
  • ROS Bag Buffer Issue
  • Check ROS Bag Health Condition

Was this helpful?

  1. Development
  2. ROS

rosbag

PreviousroslaunchNextmulti-threaded spinner

Last updated 6 months ago

Was this helpful?

ROS Bag Buffer Issue

In short, the problem is that the current data collection speed is greater than the maximum memory access bandwidth, such that more and more data are queued in the buffer and eventually results in queue overflow. In other words, rosbag is collecting too much data in a short time, such that the operating system cannot write them all in the memory/disk.

There is no actual solution to this issue, as you may always want to record more data at the same time. Some walkarounds are as follows.

  • On the recording side, you can 1) reduce the image resolution, 2) reduce the frame rate, or 3) reduce the number of topics to be recorded at the same time. The main objective is to reduce the amount of data written to the memory/disk.

  • On the memory side, if the system is working on a removable disk (e.g., SD card), you can try to replace it with a faster one. If it is on your native laptop, as you know, it is hard to replace the disk. (If you can, replacing the traditional disk with SSD would help.)

  • On the buffer side, you may use command rosbag record -b 2048 <topic name> to extend the buffer size. This can postpone the queue overflow (where the warning happens), and give you a bit more time to collect data.

  • If using the above command, please note that you have to wait for a while after you terminate the rosbag command, and make sure the xxx.bag.active file has been transformed into xxx.bag file. (Some threads in the backend are still working on the rest of data in the buffer.)

Check ROS Bag Health Condition

In the above example, one may ask "What would happen if this warning prompted?" or "Can I just use this bag file given that some messages are dropped?".

An example of healthy ROS bag looks like the following.

How to tell if it is healthy or not? You can just check if the number of messages is reasonable or not. The total record time is 113 sec, and /fcu/imu topic has 1140 messages. It means that this topic is running at roughly 10Hz. Similarly, we can infer that the camera frame rate is 20Hz, the raw imu is running at 200Hz, and vicon is running at 100Hz.

An example of unhealthy ROS bag could be the following.

In this case, the total record time is 116 sec. Therefore, given the frame rate of 20Hz, we expect that the image_raw topic should have about 2320 messages. However, the first camera cam0 only has 1922 messages. It lost 300 messages during the data collection process, perhaps due to the similar buffer issue. This may affect the performance of the algorithms running on the dataset in the future.

References: ,

To check if a bag file is healthy or not, there is a useful command rosbag info xxx.bag. In the following, let's see two examples from .

References: ,

The rosbag record problem
rosbag wiki
EuRoC MAV Dataset
EuRoC MAV Dataset
rosbag wiki
an example of healthy ROS bag
an example of unhealthy ROS bag