Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Atomic refactor for lock-free ringbuffer [Foxy] #302

Open
wants to merge 3 commits into
base: ros2-foxy
Choose a base branch
from

Conversation

Imaniac230
Copy link

@Imaniac230 Imaniac230 commented Feb 21, 2024

Related Issues & PRs

Summary of Changes

A proposed refactor of the ThreadSafeRingBuffer using std::atomic variables for lock-free access.

Changes:

  1. Blocking read and write methods continue to rely on condition variables for buffer full and empty estimation. The locks are only held for the duration of wait and once wait is finished, the operations are performed atomically.
  2. The write_overwrite method is now non-blocking, meaning it will atomically overwrite the last item imemdiately. This will not push the read_idx forward if an overwrite occurs.
  3. The read_timeout method continues to rely on the condition variable for buffer empty estimation. Lock is only held for the duration of wait_for. If the wait_for is successful, it will perform the read atomically. If the wait_for timeouts, it will simply not perform the callback (instead of returning a nullptr) and unlock the lock.
  4. Implemented non-blocking write_nonblock and read_nonblock methods, which return immediately and only perform the read or write operation if the empty and full conditions are met. These conditions are checked atomically.
  5. The read and write indexes are atomically incremented before the the actual operation takes place, instead of after. This way we can for example assume that the writer currently has "ownership" of the data pointed to by the current write_idx and might be performing a write. If the index was incremented afterwards, it's current/actual value would be basically meaningless.

I've taken some liberty with the following changes, which may not be desired but make more sense in my limited understanding:

  1. We will not be returning a nullptr in any case. If the corresponding conditions for a nonblocking or timeouted operation are not met we simply don't perform the callback operation and don't modify the buffer active size. I find it safer to just ignore the callback instead of returning an invalid pointer, which then must be handled safely by the caller.
  2. The overwriting method will not push the reading index forward if the buffer is being overwritten. This is no longer desirable if both, the reading and writing thread modify the index asynchronously. The writer can keep overwriting the buffer as many times and as fast as it can, and the reader will simply continue at it's own pace. The only thing we have to make sure of is that they both never attempt to access the same field at the same time, which is assured by atomic access to the indexes.
  3. To make sure the reader and writer will not attempt to acces the same index at the same time, there are two rules:
    1. The writer can modify any data at any time (overwrite method), or any data as long as it has available space (other methods).
    2. The reader must check that the index it wants to read from is not the same as the current write index. The read is only performed if this condition is met.

Validation

TODO: add images or videos of vizualizations, with comparisons between old, new, and community
TODO: add debug outputs from running driver
TODO: finish implementing new tests

  1. Validated using a real product (OS-0-128, sn: 122312000594, firmware rev: v3.0.1):
    • write/read
    • write_overwrite/read_timeout
    • write_nonblock/read_nonblock
  2. Validated with passing tests:
    • write/read
    • write_overwrite/read_timeout
    • write_nonblock/read_nonblock

… locks, port unique_lock creation into constructor and only perform lock/unlock operations in callbacks.

* Both blocking read and write callbacks continue to rely on condition variables for data availability.
* The write_overwrite callback now relies only on the atomic operations without locks, and does not push the read index if overwriting.
* The read_timeout callback will simply not perform the callback instead of returning a nullptr.
* Implemented true nonblocking read_nonblock and write_nonblock callbacks, which rely only on the atomic operations and return immediately either performing or not performing the callback.
…lementation.

* Adjusted current tests for the lock-free behavior.
* Added tests for the non-blocking implementation.
* Implemented new tests for scenarios, where one thread always runs slower than the other.
…rDriver as well.

* Utilizing the PacketMsg data structure to have the pointed-to buffer data transferred immediately once received and use the stable copy for further processing, instead of a reference to potentially mutable underlying data.
@Imaniac230
Copy link
Author

Imaniac230 commented Mar 6, 2024

Update

This took a bit longer than I initially wanted. There were some digressions, regressions and fixes, but now I believe it should be even more stable than the community version. When experimenting with the edge cases (multiple subscribers, buffer overfills and recoveries back to normal), I often encountered cases when older packets were being sent to the ScanBatcher processing. Their frame_id values were often older by more than just one previous frame, so the condition ls.frame_id == static_cast<uint16_t>(f_id + 1) would not catch that and the accumulation would not recover from these situations. This was also happening with the community implementation, and initially I had a "solution" in the batcher code to check for any previous frames (ls.frame_id > f_id). This was obviously a bad idea, but I found out the long way and instead used just an extended check:

inline static bool packet_from_previous_frames(const uint16_t current_f_id, const uint16_t new_f_id, const uint16_t threshold) {
        for (uint16_t previous = 1; previous <= threshold; ++previous)
            if (current_f_id == static_cast<uint16_t>(new_f_id + previous)) return true;

        return false;
    }

This worked fine and does drop the old packets so batching can recover, however, the root cause of the issue was a bug in the community driver's ringbuffer. The community version basically uses an overwriting implementation. But if the buffer was already fully overwritten the reader would be allowed to overtake the writer and read out older packets, giving the batcher older frame_id values.

This driver (and this PR refactor) would not allow that when using the overwrite method, sice the reader is not allowed to access the index held by the writer and would, therefore, not move past it. I had a small setback here, because my initial handling of the active_items_counter was not truly atomic and was causing a bug when using the non-overwrite methods (the writer would sometimes overtake the reader after filling the buffer and that would cause a deadlock situation). So now, when all operations are handled correctly, these conditions should always be met:

  1. When using overwrite: The reader should never be allowed to overtake the writer even if there are active items in the buffer (items past the writer would contain older data, and that would have to be handled by the SDK).
  2. When using non-overwrite: The writer should never overtake the reader when (after) it fills up the buffer (this would block further reading since the writer took ownership of the next index, but the writer would not move further because the buffer is already full).

So currently, I am not using any changes in the SDK code, since all of my problems were solved in this PR by better ringbuffer handling. But, I'm not sure if the wider history checks (as shown above) wouldn't be something that's desired to also have in the SDK. In my testing getting older frames in the batcher practically never happens if the ringbuffer reading is done correctly, so the loop would add additional processing under normal operation. But if it does happen it was usually more than just one previous frame, so checking just for + 1 did not have a meaningful effect.

Regarding the reading/writing rules from #302 (comment), one might ask: why allow the write operations at any time and limit the reading operations? Wouldn't it be safer to limit the unsafe write operations and allow reading at any time?

  • It would in principle, but it would also create gaps in the data and disorganize the cloud. We want to always have the latest data available from the sensor in the buffer (if it can be filled or overwritten), and it shouldn't be artificially dropped depending on the performance of the reading operations. Only the reader should decide if it can use or drop the data, but it should always be valid in the buffer.

Additional changes

Commit 455aff2: I made the lidar_packet and imu_packet members protected, and on_lidar_packet_msg and on_imu_packet_msg callback methods private. And instead, I added virtual process_lidar_packet and process_imu_packet methods, which should be using the copies in lidar_packet and imu_packet for processing. This is to make sure we transfer the pointed-to data immediately and use the stable copy for processing, instead of a reference to potentially mutable underlying data. It is already implemented in the inherited OusterSensor so I think the OusterDriver could also be utilizing this.

Validation

All of these validations were using the master SDK branch, so no changes were applied to the SDK.
Testing configuration:

  • CPU: AMD Ryzen 7 3700X @ 4GHz
  • mode: 1024x20 @ RNG19_RFL8_SIG16_NIR16 (I'm showing only this lidar mode setting, since this should be representing the worst case scenario.)
  1. normal operation: 1-2 subscribers

    • ros2_ouster (community)

      overwrite
      ros2_ouster_normal_onesub.mp4
      [ouster_driver-1] unprocessed packets: 26 (written: 28736, read: 28710)
      [ouster_driver-1] buffer active items: 26 (head: 38, tail: 64, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 26 (written: 28800, read: 28774)
      [ouster_driver-1] buffer active items: 26 (head: 102, tail: 128, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 27 (written: 28865, read: 28838)
      [ouster_driver-1] buffer active items: 27 (head: 166, tail: 193, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 25 (written: 28927, read: 28902)
      [ouster_driver-1] buffer active items: 25 (head: 230, tail: 255, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 29 (written: 28995, read: 28966)
      [ouster_driver-1] buffer active items: 29 (head: 294, tail: 323, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 26 (written: 29056, read: 29030)
      [ouster_driver-1] buffer active items: 26 (head: 358, tail: 384, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 26 (written: 29120, read: 29094)
      [ouster_driver-1] buffer active items: 26 (head: 422, tail: 448, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 28 (written: 29186, read: 29158)
      [ouster_driver-1] buffer active items: 28 (head: 486, tail: 514, full: 0, empty: 0)
      
    • ouster_ros (this old)

      write_overwrite + read
      old_ouster_ros_normal_onesub_wo_r.mp4
      [os_driver-1] unprocessed packets: 6 (written: 10968, read: 10962)
      [os_driver-1] buffer active items: 6 (ridx: 722, widx: 728, full: 0, empty: 0)
      [os_driver-1] [1709744128275376334] missing 14 packets (last m_id: 191, new m_id: 416, time diff:     542188 ns)
      [os_driver-1] unprocessed packets: 6 (written: 11018, read: 11012)
      [os_driver-1] buffer active items: 6 (ridx: 772, widx: 778, full: 0, empty: 0)
      [os_driver-1] [1709744128325372846] missing 14 packets (last m_id: 191, new m_id: 416, time diff:     253381 ns)
      [os_driver-1] [1709744128377877566] missing 17 packets (last m_id: 191, new m_id: 464, time diff:       6322 ns)
      [os_driver-1] unprocessed packets: 8 (written: 11069, read: 11061)
      [os_driver-1] buffer active items: 8 (ridx: 821, widx: 829, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 11106, read: 11105)
      [os_driver-1] buffer active items: 2 (ridx: 865, widx: 867, full: 0, empty: 0)
      [os_driver-1] [1709744128424887473] missing 13 packets (last m_id: 191, new m_id: 400, time diff:       8887 ns)
      [os_driver-1] unprocessed packets: 5 (written: 11166, read: 11161)
      [os_driver-1] buffer active items: 5 (ridx: 921, widx: 926, full: 0, empty: 0)
      
      write + read
      old_ouster_ros_normal_onesub_w_r.mp4
      [os_driver-1] unprocessed packets: 7 (written: 16264, read: 16257)
      [os_driver-1] buffer active items: 7 (ridx: 897, widx: 904, full: 0, empty: 0)
      [os_driver-1] [1709745488769176291] missing 13 packets (last m_id: 191, new m_id: 400, time diff:     766553 ns)
      [os_driver-1] unprocessed packets: 1 (written: 16306, read: 16305)
      [os_driver-1] buffer active items: 2 (ridx: 945, widx: 947, full: 0, empty: 0)
      [os_driver-1] [1709745488820748285] missing 15 packets (last m_id: 191, new m_id: 432, time diff:     539884 ns)
      [os_driver-1] [1709745488868186532] missing 12 packets (last m_id: 191, new m_id: 384, time diff:       5420 ns)
      [os_driver-1] unprocessed packets: 8 (written: 16365, read: 16357)
      [os_driver-1] buffer active items: 8 (ridx: 997, widx: 1005, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6 (written: 16416, read: 16410)
      [os_driver-1] buffer active items: 6 (ridx: 26, widx: 32, full: 0, empty: 0)
      [os_driver-1] [1709745488918951205] missing 13 packets (last m_id: 191, new m_id: 400, time diff:      89229 ns)
      [os_driver-1] unprocessed packets: 1 (written: 16459, read: 16458)
      [os_driver-1] buffer active items: 9 (ridx: 74, widx: 83, full: 0, empty: 0)
      
    • ouster_ros (this new)

      write_nonblock + read
      new_ouster_ros_normal_onesub_wn_r.mp4
      [os_driver-1] buffer active items: 26 (ridx: 443, widx: 468, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 67055, read: 67054)
      [os_driver-1] buffer active items: 2 (ridx: 493, widx: 494, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 67095, read: 67068)
      [os_driver-1] buffer active items: 28 (ridx: 507, widx: 534, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 67126, read: 67125)
      [os_driver-1] buffer active items: 2 (ridx: 564, widx: 565, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 67156, read: 67132)
      [os_driver-1] buffer active items: 25 (ridx: 571, widx: 595, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 67220, read: 67196)
      [os_driver-1] buffer active items: 25 (ridx: 635, widx: 659, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 67286, read: 67260)
      [os_driver-1] buffer active items: 27 (ridx: 699, widx: 725, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 67349, read: 67324)
      [os_driver-1] buffer active items: 26 (ridx: 763, widx: 788, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 67382, read: 67381)
      [os_driver-1] buffer active items: 2 (ridx: 820, widx: 821, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 67412, read: 67388)
      
      write_nonblock + read_nonblock
      new_ouster_ros_normal_onesub_wn_rn.mp4
      [os_driver-1] unprocessed packets: 1 (written: 11750, read: 11749)
      [os_driver-1] buffer active items: 2 (ridx: 484, widx: 485, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 11783, read: 11755)
      [os_driver-1] buffer active items: 29 (ridx: 490, widx: 518, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 11843, read: 11819)
      [os_driver-1] buffer active items: 25 (ridx: 554, widx: 578, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 11878, read: 11877)
      [os_driver-1] buffer active items: 2 (ridx: 612, widx: 613, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 11908, read: 11883)
      [os_driver-1] buffer active items: 26 (ridx: 618, widx: 643, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 11971, read: 11947)
      [os_driver-1] buffer active items: 25 (ridx: 682, widx: 706, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 12001, read: 12000)
      
      write_overwrite + read
      new_ouster_ros_normal_onesub_wo_r.mp4
      [os_driver-1] buffer active items: 26 (ridx: 90, widx: 115, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 6324, read: 6299)
      [os_driver-1] buffer active items: 26 (ridx: 154, widx: 179, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 6387, read: 6363)
      [os_driver-1] buffer active items: 25 (ridx: 218, widx: 242, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 6418, read: 6417)
      [os_driver-1] buffer active items: 2 (ridx: 272, widx: 273, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 6452, read: 6427)
      [os_driver-1] buffer active items: 26 (ridx: 282, widx: 307, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 6517, read: 6491)
      [os_driver-1] buffer active items: 27 (ridx: 346, widx: 372, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 6549, read: 6548)
      [os_driver-1] buffer active items: 2 (ridx: 403, widx: 404, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 6579, read: 6555)
      [os_driver-1] buffer active items: 25 (ridx: 410, widx: 434, full: 0, empty: 0)
      
      write_overwrite + read_nonblock
      new_ouster_ros_normal_onesub_wo_rn.mp4
      [os_driver-1] unprocessed packets: 25 (written: 6699, read: 6674)
      [os_driver-1] buffer active items: 26 (ridx: 529, widx: 554, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 6762, read: 6738)
      [os_driver-1] buffer active items: 25 (ridx: 593, widx: 617, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 6826, read: 6802)
      [os_driver-1] buffer active items: 26 (ridx: 657, widx: 682, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 6858, read: 6857)
      [os_driver-1] buffer active items: 2 (ridx: 712, widx: 713, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 6891, read: 6866)
      [os_driver-1] buffer active items: 26 (ridx: 721, widx: 746, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 6955, read: 6930)
      [os_driver-1] buffer active items: 26 (ridx: 785, widx: 810, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 6981, read: 6980)
      [os_driver-1] buffer active items: 2 (ridx: 835, widx: 836, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 7018, read: 6994)
      [os_driver-1] buffer active items: 25 (ridx: 849, widx: 873, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 7084, read: 7058)
      [os_driver-1] buffer active items: 27 (ridx: 913, widx: 939, full: 0, empty: 0)
      
      write + read
      new_ouster_ros_normal_onesub_w_r.mp4
      [os_driver-1] buffer active items: 26 (ridx: 802, widx: 827, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 7035, read: 7011)
      [os_driver-1] buffer active items: 25 (ridx: 866, widx: 890, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7066, read: 7065)
      [os_driver-1] buffer active items: 2 (ridx: 920, widx: 921, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 7104, read: 7075)
      [os_driver-1] buffer active items: 30 (ridx: 930, widx: 959, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 31 (written: 7170, read: 7139)
      [os_driver-1] buffer active items: 32 (ridx: 994, widx: 1, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 7231, read: 7203)
      [os_driver-1] buffer active items: 29 (ridx: 34, widx: 62, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 7295, read: 7267)
      [os_driver-1] buffer active items: 29 (ridx: 98, widx: 126, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 7359, read: 7331)
      [os_driver-1] buffer active items: 29 (ridx: 162, widx: 190, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7388, read: 7387)
      [os_driver-1] buffer active items: 2 (ridx: 218, widx: 219, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 7422, read: 7395)
      
      write + read_nonblock
      new_ouster_ros_normal_onesub_w_rn.mp4
      [os_driver-1] unprocessed packets: 29 (written: 15857, read: 15828)
      [os_driver-1] buffer active items: 30 (ridx: 467, widx: 496, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 15917, read: 15892)
      [os_driver-1] buffer active items: 26 (ridx: 531, widx: 556, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 15950, read: 15949)
      [os_driver-1] buffer active items: 2 (ridx: 588, widx: 589, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 15981, read: 15956)
      [os_driver-1] buffer active items: 26 (ridx: 595, widx: 620, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 24 (written: 16044, read: 16020)
      [os_driver-1] buffer active items: 25 (ridx: 659, widx: 683, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 16110, read: 16084)
      [os_driver-1] buffer active items: 27 (ridx: 723, widx: 749, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 16144, read: 16143)
      [os_driver-1] buffer active items: 2 (ridx: 782, widx: 783, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 16174, read: 16148)
      [os_driver-1] buffer active items: 27 (ridx: 787, widx: 813, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 16201, read: 16200)
      [os_driver-1] buffer active items: 2 (ridx: 839, widx: 840, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 16240, read: 16212)
      [os_driver-1] buffer active items: 29 (ridx: 851, widx: 879, full: 0, empty: 0)
      
  2. overfill: adding 3rd subscriber

    • ros2_ouster (community)

      overwrite
      ros2_ouster_overfill_threesubs.mp4

      The counting here is only doing full sized _tail - _head, which are both 2*_num_elements. So it is not very reliable once they start wrapping around.

      [ouster_driver-1] unprocessed packets: 843 (written: 14227, read: 13384)
      [ouster_driver-1] buffer active items: 843 (head: 72, tail: 915, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 867 (written: 14315, read: 13448)
      [ouster_driver-1] buffer active items: 867 (head: 136, tail: 1003, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 887 (written: 14399, read: 13512)
      [ouster_driver-1] buffer active items: -1161 (head: 200, tail: 63, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 908 (written: 14484, read: 13576)
      [ouster_driver-1] buffer active items: -1140 (head: 264, tail: 148, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 927 (written: 14567, read: 13640)
      [ouster_driver-1] buffer active items: -1121 (head: 328, tail: 231, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 945 (written: 14649, read: 13704)
      [ouster_driver-1] buffer active items: -1103 (head: 392, tail: 313, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 965 (written: 14733, read: 13768)
      [ouster_driver-1] buffer active items: -1083 (head: 456, tail: 397, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 985 (written: 14817, read: 13832)
      [ouster_driver-1] buffer active items: -1063 (head: 520, tail: 481, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1002 (written: 14898, read: 13896)
      [ouster_driver-1] buffer active items: -1046 (head: 584, tail: 562, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1017 (written: 14977, read: 13960)
      [ouster_driver-1] buffer active items: -1031 (head: 648, tail: 641, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1037 (written: 15061, read: 14024)
      [ouster_driver-1] buffer active items: -1011 (head: 712, tail: 725, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1127 (written: 15152, read: 14025)
      [ouster_driver-1] buffer active items: -921 (head: 713, tail: 816, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1150 (written: 15238, read: 14088)
      [ouster_driver-1] buffer active items: -898 (head: 776, tail: 902, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1165 (written: 15317, read: 14152)
      [ouster_driver-1] buffer active items: -883 (head: 840, tail: 981, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1181 (written: 15397, read: 14216)
      [ouster_driver-1] buffer active items: -867 (head: 904, tail: 37, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1196 (written: 15476, read: 14280)
      [ouster_driver-1] buffer active items: -852 (head: 968, tail: 116, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1214 (written: 15558, read: 14344)
      [ouster_driver-1] buffer active items: 1214 (head: 8, tail: 198, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 1235 (written: 15643, read: 14408)
      [ouster_driver-1] buffer active items: 1235 (head: 72, tail: 283, full: 0, empty: 0)
      
    • ouster_ros (this old)

      write_overwrite + read
      old_ouster_ros_threesubs_wo_r.mp4
      [os_driver-1] unprocessed packets: 3 (written: 7745, read: 7742)
      [os_driver-1] buffer active items: 3 (ridx: 574, widx: 577, full: 0, empty: 0)
      [os_driver-1] [1709744268844880160] missing 44 packets (last m_id: 191, new m_id: 896, time diff:     482835 ns)
      [os_driver-1] unprocessed packets: 5 (written: 7765, read: 7760)
      [os_driver-1] buffer active items: 6 (ridx: 592, widx: 598, full: 0, empty: 0)
      [os_driver-1] [1709744268894825645] missing 44 packets (last m_id: 191, new m_id: 896, time diff:      32381 ns)
      [os_driver-1] unprocessed packets: 8 (written: 7786, read: 7778)
      [os_driver-1] buffer active items: 8 (ridx: 610, widx: 618, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7788, read: 7787)
      [os_driver-1] buffer active items: 2 (ridx: 619, widx: 621, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7809, read: 7808)
      [os_driver-1] buffer active items: 1 (ridx: 640, widx: 641, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7821, read: 7820)
      [os_driver-1] buffer active items: 1 (ridx: 652, widx: 653, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7830, read: 7829)
      [os_driver-1] buffer active items: 2 (ridx: 661, widx: 663, full: 0, empty: 0)
      [os_driver-1] [1709744269469934015] missing 1 whole frames (last f_id: 439, new f_id: 441, time diff:      33634 ns)
      [os_driver-1] unprocessed packets: 1 (written: 7876, read: 7875)
      [os_driver-1] buffer active items: 2 (ridx: 707, widx: 709, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 7878, read: 7876)
      [os_driver-1] buffer active items: 3 (ridx: 708, widx: 711, full: 0, empty: 0)
      [os_driver-1] [1709744269982315225] missing 1 whole frames (last f_id: 448, new f_id: 450, time diff:      33975 ns)
      [os_driver-1] [1709744270234813216] missing 1 whole frames (last f_id: 453, new f_id: 455, time diff:      26009 ns)
      [os_driver-1] unprocessed packets: 2 (written: 7906, read: 7904)
      [os_driver-1] buffer active items: 3 (ridx: 736, widx: 739, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 4 (written: 7910, read: 7906)
      [os_driver-1] buffer active items: 5 (ridx: 738, widx: 743, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 7911, read: 7909)
      [os_driver-1] buffer active items: 3 (ridx: 741, widx: 744, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7920, read: 7919)
      [os_driver-1] buffer active items: 2 (ridx: 751, widx: 753, full: 0, empty: 0)
      [os_driver-1] [1709744270425348157] missing 2 whole frames (last f_id: 457, new f_id: 460, time diff:      32131 ns)
      [os_driver-1] unprocessed packets: 2 (written: 7923, read: 7921)
      [os_driver-1] buffer active items: 3 (ridx: 753, widx: 756, full: 0, empty: 0)
      
      write + read
      old_ouster_ros_threesubs_w_r.mp4
      [os_driver-1] unprocessed packets: 7 (written: 5783, read: 5776)
      [os_driver-1] buffer active items: 7 (ridx: 656, widx: 663, full: 0, empty: 0)
      [os_driver-1] [1709745647839107309] missing 44 packets (last m_id: 191, new m_id: 896, time diff:     108485 ns)
      [os_driver-1] unprocessed packets: 7 (written: 5803, read: 5796)
      [os_driver-1] buffer active items: 7 (ridx: 676, widx: 683, full: 0, empty: 0)
      [os_driver-1] [1709745647888359418] missing 43 packets (last m_id: 191, new m_id: 880, time diff:     129475 ns)
      [os_driver-1] unprocessed packets: 1 (written: 5818, read: 5817)
      [os_driver-1] buffer active items: 2 (ridx: 697, widx: 699, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 5837, read: 5835)
      [os_driver-1] buffer active items: 2 (ridx: 715, widx: 717, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 5843, read: 5841)
      [os_driver-1] buffer active items: 3 (ridx: 721, widx: 724, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 3 (written: 5861, read: 5858)
      [os_driver-1] buffer active items: 3 (ridx: 738, widx: 741, full: 0, empty: 0)
      [os_driver-1] [1709745648832223336] missing 1 whole frames (last f_id: 329, new f_id: 331, time diff:      43923 ns)
      [os_driver-1] [1709745649021138555] missing 1 whole frames (last f_id: 333, new f_id: 335, time diff:      32191 ns)
      [os_driver-1] [1709745649273702585] missing 1 whole frames (last f_id: 338, new f_id: 340, time diff:      56697 ns)
      [os_driver-1] [1709745649522776978] missing 1 whole frames (last f_id: 343, new f_id: 345, time diff:      45487 ns)
      [os_driver-1] unprocessed packets: 2 (written: 5962, read: 5960)
      [os_driver-1] buffer active items: 9 (ridx: 840, widx: 849, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6 (written: 5969, read: 5963)
      [os_driver-1] buffer active items: 7 (ridx: 843, widx: 850, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 4 (written: 5970, read: 5966)
      [os_driver-1] buffer active items: 5 (ridx: 846, widx: 851, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 5971, read: 5969)
      [os_driver-1] buffer active items: 3 (ridx: 849, widx: 852, full: 0, empty: 0)
      [os_driver-1] [1709745649841650944] missing 2 whole frames (last f_id: 349, new f_id: 352, time diff:      47299 ns)
      [os_driver-1] [1709745649957867943] missing 1 whole frames (last f_id: 353, new f_id: 355, time diff:     294178 ns)
      [os_driver-1] unprocessed packets: 4 (written: 5996, read: 5992)
      [os_driver-1] buffer active items: 5 (ridx: 872, widx: 877, full: 0, empty: 0)
      
    • ouster_ros (this new)

      write_nonblock + read
      new_ouster_ros_overfill_threesubs_wn_r.mp4
      [os_driver-1] buffer active items: 949 (ridx: 135, widx: 59, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 963 (written: 41099, read: 40136)
      [os_driver-1] buffer active items: 964 (ridx: 199, widx: 138, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 980 (written: 41180, read: 40200)
      [os_driver-1] buffer active items: 981 (ridx: 263, widx: 219, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 992 (written: 41256, read: 40264)
      [os_driver-1] buffer active items: 993 (ridx: 327, widx: 295, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1015 (written: 41343, read: 40328)
      [os_driver-1] buffer active items: 1016 (ridx: 391, widx: 382, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 41414, read: 40392)
      [os_driver-1] buffer active items: 1024 (ridx: 455, widx: 454, full: 1, empty: 0)
      [os_driver-1] [1709739137248785419] missing 1 packets (last m_id: 175, new m_id: 192, time diff:     291563 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 41478, read: 40456)
      [os_driver-1] buffer active items: 1023 (ridx: 519, widx: 518, full: 0, empty: 0)
      [os_driver-1] [1709739137315286216] missing 21 packets (last m_id: 191, new m_id: 528, time diff:     788135 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 41542, read: 40520)
      [os_driver-1] buffer active items: 1023 (ridx: 583, widx: 582, full: 0, empty: 0)
      
      write_nonblock + read_nonblock
      new_ouster_ros_overfill_threesubs_wn_rn.mp4
      [os_driver-1] unprocessed packets: 975 (written: 21897, read: 20922)
      [os_driver-1] buffer active items: 976 (ridx: 441, widx: 392, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 988 (written: 21974, read: 20986)
      [os_driver-1] buffer active items: 989 (ridx: 505, widx: 469, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1003 (written: 22053, read: 21050)
      [os_driver-1] buffer active items: 1004 (ridx: 569, widx: 548, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1015 (written: 22129, read: 21114)
      [os_driver-1] buffer active items: 1016 (ridx: 633, widx: 624, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 22200, read: 21178)
      [os_driver-1] buffer active items: 1024 (ridx: 697, widx: 696, full: 1, empty: 0)
      [os_driver-1] [1709740097027714605] missing 2 packets (last m_id: 175, new m_id: 208, time diff:      45406 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 22264, read: 21242)
      [os_driver-1] buffer active items: 1023 (ridx: 761, widx: 760, full: 0, empty: 0)
      [os_driver-1] [1709740097088817459] missing 14 packets (last m_id: 207, new m_id: 432, time diff:     237050 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 22328, read: 21306)
      [os_driver-1] buffer active items: 1023 (ridx: 825, widx: 824, full: 0, empty: 0)
      
      write_overwrite + read
      new_ouster_ros_overfill_threesubs_wo_r.mp4
      [os_driver-1] unprocessed packets: 971 (written: 20411, read: 19440)
      [os_driver-1] buffer active items: 972 (ridx: 1007, widx: 954, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 990 (written: 20494, read: 19504)
      [os_driver-1] buffer active items: 991 (ridx: 47, widx: 13, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1014 (written: 20582, read: 19568)
      [os_driver-1] buffer active items: 1015 (ridx: 111, widx: 101, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1032 (written: 20664, read: 19632)
      [os_driver-1] buffer active items: 1023 (ridx: 175, widx: 183, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1112 (written: 20745, read: 19633)
      [os_driver-1] buffer active items: 1023 (ridx: 176, widx: 264, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1132 (written: 20828, read: 19696)
      [os_driver-1] buffer active items: 1023 (ridx: 239, widx: 347, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1150 (written: 20910, read: 19760)
      [os_driver-1] buffer active items: 1023 (ridx: 303, widx: 429, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1168 (written: 20992, read: 19824)
      [os_driver-1] buffer active items: 1023 (ridx: 367, widx: 511, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1191 (written: 21079, read: 19888)
      [os_driver-1] buffer active items: 1023 (ridx: 431, widx: 598, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1208 (written: 21160, read: 19952)
      [os_driver-1] buffer active items: 1023 (ridx: 495, widx: 679, full: 0, empty: 0)
      
      write_overwrite + read_nonblock
      new_ouster_ros_overfill_threesubs_wo_rn.mp4
      [os_driver-1] unprocessed packets: 941 (written: 20960, read: 20019)
      [os_driver-1] buffer active items: 942 (ridx: 562, widx: 479, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 959 (written: 21042, read: 20083)
      [os_driver-1] buffer active items: 960 (ridx: 626, widx: 561, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 984 (written: 21131, read: 20147)
      [os_driver-1] buffer active items: 985 (ridx: 690, widx: 650, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1006 (written: 21217, read: 20211)
      [os_driver-1] buffer active items: 1007 (ridx: 754, widx: 736, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1020 (written: 21295, read: 20275)
      [os_driver-1] buffer active items: 1021 (ridx: 818, widx: 814, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1031 (written: 21370, read: 20339)
      [os_driver-1] buffer active items: 1023 (ridx: 882, widx: 889, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1100 (written: 21440, read: 20340)
      [os_driver-1] buffer active items: 1023 (ridx: 883, widx: 959, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1125 (written: 21528, read: 20403)
      [os_driver-1] buffer active items: 1023 (ridx: 946, widx: 23, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1159 (written: 21626, read: 20467)
      [os_driver-1] buffer active items: 1023 (ridx: 1010, widx: 121, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1185 (written: 21716, read: 20531)
      [os_driver-1] buffer active items: 1023 (ridx: 50, widx: 211, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1200 (written: 21795, read: 20595)
      [os_driver-1] buffer active items: 1023 (ridx: 114, widx: 290, full: 0, empty: 0)
      
      write + read
      new_ouster_ros_overfill_threesubs_w_r.mp4
      [os_driver-1] unprocessed packets: 946 (written: 18549, read: 17603)
      [os_driver-1] buffer active items: 947 (ridx: 194, widx: 116, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 958 (written: 18625, read: 17667)
      [os_driver-1] buffer active items: 960 (ridx: 258, widx: 193, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 979 (written: 18710, read: 17731)
      [os_driver-1] buffer active items: 980 (ridx: 322, widx: 277, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 990 (written: 18785, read: 17795)
      [os_driver-1] buffer active items: 991 (ridx: 386, widx: 352, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 997 (written: 18856, read: 17859)
      [os_driver-1] buffer active items: 998 (ridx: 450, widx: 423, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1008 (written: 18931, read: 17923)
      [os_driver-1] buffer active items: 1009 (ridx: 514, widx: 498, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1016 (written: 19003, read: 17987)
      [os_driver-1] buffer active items: 1017 (ridx: 578, widx: 570, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 19073, read: 18051)
      [os_driver-1] buffer active items: 1024 (ridx: 642, widx: 641, full: 1, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 19137, read: 18115)
      [os_driver-1] buffer active items: 1023 (ridx: 706, widx: 705, full: 0, empty: 0)
      [os_driver-1] [1709742306317285329] missing 7 packets (last m_id: 175, new m_id: 288, time diff:      92545 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 19201, read: 18179)
      [os_driver-1] buffer active items: 1023 (ridx: 770, widx: 769, full: 0, empty: 0)
      [os_driver-1] [1709742306376842580] missing 12 packets (last m_id: 287, new m_id: 480, time diff:      18796 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 19265, read: 18243)
      [os_driver-1] buffer active items: 1023 (ridx: 834, widx: 833, full: 0, empty: 0)
      
      write + read_nonblock
      new_ouster_ros_overfill_threesubs_w_rn.mp4
      [os_driver-1] unprocessed packets: 949 (written: 20340, read: 19391)
      [os_driver-1] buffer active items: 950 (ridx: 958, widx: 883, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 970 (written: 20425, read: 19455)
      [os_driver-1] buffer active items: 971 (ridx: 1022, widx: 968, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 996 (written: 20515, read: 19519)
      [os_driver-1] buffer active items: 997 (ridx: 62, widx: 34, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1017 (written: 20600, read: 19583)
      [os_driver-1] buffer active items: 1018 (ridx: 126, widx: 119, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 20669, read: 19647)
      [os_driver-1] buffer active items: 1023 (ridx: 190, widx: 189, full: 0, empty: 0)
      [os_driver-1] [1709742819931417570] missing 4 packets (last m_id: 175, new m_id: 240, time diff:     283237 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 20733, read: 19711)
      [os_driver-1] buffer active items: 1023 (ridx: 254, widx: 253, full: 0, empty: 0)
      [os_driver-1] [1709742820001127028] missing 25 packets (last m_id: 239, new m_id: 640, time diff:      72618 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 20797, read: 19775)
      [os_driver-1] buffer active items: 1023 (ridx: 318, widx: 317, full: 0, empty: 0)
      
  3. recovery from overfill: from 5 subscribers to 1

    • ros2_ouster (community)

      overwrite
      ros2_ouster_recovery_bad.mp4

      The counting here is only doing full sized _tail - _head, which are both 2*_num_elements. So it is not very reliable once they start wrapping around.

      [ouster_driver-1] unprocessed packets: 6829 (written: 12045, read: 5216)
      [ouster_driver-1] buffer active items: 685 (head: 96, tail: 781, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 6889 (written: 12169, read: 5280)
      [ouster_driver-1] buffer active items: 745 (head: 160, tail: 905, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 6950 (written: 12294, read: 5344)
      [ouster_driver-1] buffer active items: -1242 (head: 224, tail: 6, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7023 (written: 12431, read: 5408)
      [ouster_driver-1] buffer active items: -1169 (head: 288, tail: 143, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7093 (written: 12565, read: 5472)
      [ouster_driver-1] buffer active items: -1099 (head: 352, tail: 277, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7167 (written: 12703, read: 5536)
      [ouster_driver-1] buffer active items: -1025 (head: 416, tail: 415, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7235 (written: 12835, read: 5600)
      [ouster_driver-1] buffer active items: -957 (head: 480, tail: 547, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7260 (written: 12861, read: 5601)
      [ouster_driver-1] buffer active items: -932 (head: 481, tail: 573, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7229 (written: 12893, read: 5664)
      [ouster_driver-1] buffer active items: -962 (head: 544, tail: 606, full: 0, empty: 0)
      [ouster_driver-1] [1709747058180165301] batcher -> got old packet, ls.frame_id - f_id = 15 (current f_id: 20882, new f_id: 20867)
      [ouster_driver-1] unprocessed packets: 7199 (written: 12927, read: 5728)
      [ouster_driver-1] buffer active items: -993 (head: 608, tail: 639, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7229 (written: 12958, read: 5729)
      [ouster_driver-1] buffer active items: -963 (head: 609, tail: 670, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 7198 (written: 12990, read: 5792)
      [ouster_driver-1] buffer active items: -994 (head: 672, tail: 702, full: 0, empty: 0)
      [ouster_driver-1] [1709747058254503130] batcher -> got old packet, ls.frame_id - f_id = 16 (current f_id: 20884, new f_id: 20868)
      [ouster_driver-1] unprocessed packets: 7197 (written: 13020, read: 5823)
      [ouster_driver-1] buffer active items: -995 (head: 703, tail: 732, full: 0, empty: 0)
      
      ros2_ouster_recovery_good.mp4

      The counting here is only doing full sized _tail - _head, which are both 2*_num_elements. So it is not very reliable once they start wrapping around.

      [ouster_driver-1] unprocessed packets: 3990 (written: 7197, read: 3207)
      [ouster_driver-1] buffer active items: -106 (head: 135, tail: 29, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4046 (written: 7317, read: 3271)
      [ouster_driver-1] buffer active items: -50 (head: 199, tail: 149, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4100 (written: 7435, read: 3335)
      [ouster_driver-1] buffer active items: 4 (head: 263, tail: 267, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4230 (written: 7566, read: 3336)
      [ouster_driver-1] buffer active items: 134 (head: 264, tail: 398, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4282 (written: 7681, read: 3399)
      [ouster_driver-1] buffer active items: 186 (head: 327, tail: 513, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4344 (written: 7807, read: 3463)
      [ouster_driver-1] buffer active items: 248 (head: 391, tail: 639, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4311 (written: 7838, read: 3527)
      [ouster_driver-1] buffer active items: 215 (head: 455, tail: 670, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4277 (written: 7868, read: 3591)
      [ouster_driver-1] buffer active items: 181 (head: 519, tail: 700, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4241 (written: 7896, read: 3655)
      [ouster_driver-1] buffer active items: 145 (head: 583, tail: 728, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4208 (written: 7927, read: 3719)
      [ouster_driver-1] buffer active items: 112 (head: 647, tail: 759, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4178 (written: 7961, read: 3783)
      [ouster_driver-1] buffer active items: 82 (head: 711, tail: 793, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4148 (written: 7995, read: 3847)
      [ouster_driver-1] buffer active items: 52 (head: 775, tail: 827, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4138 (written: 8049, read: 3911)
      [ouster_driver-1] buffer active items: 42 (head: 839, tail: 881, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4128 (written: 8103, read: 3975)
      [ouster_driver-1] buffer active items: 32 (head: 903, tail: 935, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4096 (written: 8130, read: 4034)
      [ouster_driver-1] buffer active items: 0 (head: 962, tail: 962, full: 0, empty: 1)
      [ouster_driver-1] unprocessed packets: 4125 (written: 8165, read: 4039)
      [ouster_driver-1] buffer active items: 30 (head: 967, tail: 997, full: 0, empty: 0)
      [ouster_driver-1] unprocessed packets: 4096 (written: 8191, read: 4095)
      [ouster_driver-1] buffer active items: 0 (head: 1023, tail: 1023, full: 0, empty: 1)
      
    • ouster_ros (this old)

      write_overwrite + read
      old_ouster_ros_recovery_wo_r.mp4
      [os_driver-1] unprocessed packets: 3 (written: 1032, read: 1029)
      [os_driver-1] buffer active items: 4 (ridx: 5, widx: 9, full: 0, empty: 0)
      [os_driver-1] [1709744456673216415] missing 1 whole frames (last f_id: 322, new f_id: 324, time diff:      46578 ns)
      [os_driver-1] [1709744456773297016] missing 1 whole frames (last f_id: 324, new f_id: 326, time diff:     453831 ns)
      [os_driver-1] unprocessed packets: 3 (written: 1055, read: 1052)
      [os_driver-1] buffer active items: 4 (ridx: 28, widx: 32, full: 0, empty: 0)
      [os_driver-1] [1709744456874502541] missing 1 whole frames (last f_id: 326, new f_id: 328, time diff:      23104 ns)
      [os_driver-1] [1709744456954505650] missing 1 whole frames (last f_id: 328, new f_id: 330, time diff:     505950 ns)
      [os_driver-1] unprocessed packets: 8 (written: 1080, read: 1072)
      [os_driver-1] buffer active items: 8 (ridx: 48, widx: 56, full: 0, empty: 0)
      [os_driver-1] [1709744456980380780] missing 21 packets (last m_id: 319, new m_id: 656, time diff:     586202 ns)
      [os_driver-1] unprocessed packets: 7 (written: 1115, read: 1108)
      [os_driver-1] buffer active items: 7 (ridx: 84, widx: 91, full: 0, empty: 0)
      [os_driver-1] [1709744457017800437] missing 13 packets (last m_id: 191, new m_id: 400, time diff:     374791 ns)
      [os_driver-1] unprocessed packets: 6 (written: 1166, read: 1160)
      [os_driver-1] buffer active items: 6 (ridx: 136, widx: 142, full: 0, empty: 0)
      
      write + read
      old_ouster_ros_recovery_w_r.mp4
      [os_driver-1] unprocessed packets: 1 (written: 1064, read: 1063)
      [os_driver-1] buffer active items: 2 (ridx: 39, widx: 41, full: 0, empty: 0)
      [os_driver-1] [1709745777077863956] missing 1 whole frames (last f_id: 290, new f_id: 292, time diff:      52109 ns)
      [os_driver-1] [1709745777171086286] missing 1 whole frames (last f_id: 292, new f_id: 294, time diff:      57629 ns)
      [os_driver-1] [1709745777261475132] missing 1 whole frames (last f_id: 294, new f_id: 296, time diff:     107524 ns)
      [os_driver-1] [1709745777361870134] missing 1 whole frames (last f_id: 296, new f_id: 298, time diff:      70684 ns)
      [os_driver-1] [1709745777463585881] missing 1 whole frames (last f_id: 298, new f_id: 300, time diff:      37682 ns)
      [os_driver-1] unprocessed packets: 1 (written: 1096, read: 1095)
      [os_driver-1] buffer active items: 3 (ridx: 71, widx: 74, full: 0, empty: 0)
      [os_driver-1] [1709745777463773817] missing 1 whole frames (last f_id: 300, new f_id: 302, time diff:      37461 ns)
      [os_driver-1] unprocessed packets: 7 (written: 1103, read: 1096)
      [os_driver-1] buffer active items: 8 (ridx: 72, widx: 80, full: 0, empty: 0)
      [os_driver-1] [1709745777554546752] missing 1 whole frames (last f_id: 302, new f_id: 304, time diff:      23404 ns)
      [os_driver-1] unprocessed packets: 5 (written: 1110, read: 1105)
      [os_driver-1] buffer active items: 6 (ridx: 81, widx: 87, full: 0, empty: 0)
      [os_driver-1] [1709745777598862754] missing 1 whole frames (last f_id: 304, new f_id: 306, time diff:      28584 ns)
      [os_driver-1] unprocessed packets: 2 (written: 1118, read: 1116)
      [os_driver-1] buffer active items: 8 (ridx: 92, widx: 100, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 2 (written: 1124, read: 1122)
      [os_driver-1] buffer active items: 4 (ridx: 98, widx: 102, full: 0, empty: 0)
      [os_driver-1] [1709745777644738735] missing 27 packets (last m_id: 207, new m_id: 640, time diff:   22638463 ns)
      [os_driver-1] unprocessed packets: 1 (written: 1138, read: 1137)
      [os_driver-1] buffer active items: 2 (ridx: 113, widx: 115, full: 0, empty: 0)
      [os_driver-1] [1709745777667944192] missing 17 packets (last m_id: 271, new m_id: 544, time diff:     474961 ns)
      [os_driver-1] unprocessed packets: 6 (written: 1189, read: 1183)
      [os_driver-1] buffer active items: 6 (ridx: 159, widx: 165, full: 0, empty: 0)
      [os_driver-1] [1709745777717210362] missing 21 packets (last m_id: 191, new m_id: 528, time diff:     144344 ns)
      [os_driver-1] unprocessed packets: 7 (written: 1232, read: 1225)
      [os_driver-1] buffer active items: 7 (ridx: 201, widx: 208, full: 0, empty: 0)
      
    • ouster_ros (this new)

      write_nonblock + read
      new_ouster_ros_recovery_wn_r.mp4
      [os_driver-1] unprocessed packets: 1022 (written: 16140, read: 15118)
      [os_driver-1] buffer active items: 1024 (ridx: 781, widx: 780, full: 1, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 16162, read: 15140)
      [os_driver-1] buffer active items: 1024 (ridx: 803, widx: 802, full: 1, empty: 0)
      [os_driver-1] [1709739336874787050] missing 8 packets (last m_id: 719, new m_id: 848, time diff:     545605 ns)
      [os_driver-1] unprocessed packets: 1012 (written: 16203, read: 15191)
      [os_driver-1] buffer active items: 1013 (ridx: 854, widx: 842, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 984 (written: 16239, read: 15255)
      [os_driver-1] buffer active items: 985 (ridx: 918, widx: 878, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 954 (written: 16270, read: 15316)
      [os_driver-1] buffer active items: 955 (ridx: 979, widx: 909, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 934 (written: 16301, read: 15367)
      [os_driver-1] buffer active items: 935 (ridx: 6, widx: 940, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 900 (written: 16331, read: 15431)
      [os_driver-1] buffer active items: 901 (ridx: 70, widx: 970, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 868 (written: 16363, read: 15495)
      [os_driver-1] buffer active items: 869 (ridx: 134, widx: 1002, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 837 (written: 16393, read: 15556)
      [os_driver-1] buffer active items: 838 (ridx: 195, widx: 8, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 818 (written: 16424, read: 15606)
      [os_driver-1] buffer active items: 819 (ridx: 245, widx: 39, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 792 (written: 16456, read: 15664)
      [os_driver-1] buffer active items: 793 (ridx: 303, widx: 71, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 769 (written: 16490, read: 15721)
      [os_driver-1] buffer active items: 770 (ridx: 360, widx: 105, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 736 (written: 16521, read: 15785)
      [os_driver-1] buffer active items: 737 (ridx: 424, widx: 136, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 704 (written: 16553, read: 15849)
      [os_driver-1] buffer active items: 705 (ridx: 488, widx: 168, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 686 (written: 16584, read: 15898)
      [os_driver-1] buffer active items: 687 (ridx: 537, widx: 199, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 654 (written: 16615, read: 15961)
      [os_driver-1] buffer active items: 655 (ridx: 600, widx: 230, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 668 (written: 16646, read: 15978)
      [os_driver-1] buffer active items: 669 (ridx: 617, widx: 261, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 653 (written: 16677, read: 16024)
      [os_driver-1] buffer active items: 654 (ridx: 663, widx: 292, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 629 (written: 16708, read: 16079)
      [os_driver-1] buffer active items: 630 (ridx: 718, widx: 323, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 612 (written: 16742, read: 16130)
      [os_driver-1] buffer active items: 613 (ridx: 769, widx: 357, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 587 (written: 16773, read: 16186)
      [os_driver-1] buffer active items: 588 (ridx: 825, widx: 388, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 554 (written: 16804, read: 16250)
      [os_driver-1] buffer active items: 555 (ridx: 889, widx: 419, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 520 (written: 16834, read: 16314)
      [os_driver-1] buffer active items: 521 (ridx: 953, widx: 449, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 488 (written: 16866, read: 16378)
      [os_driver-1] buffer active items: 489 (ridx: 1017, widx: 481, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 455 (written: 16897, read: 16442)
      [os_driver-1] buffer active items: 456 (ridx: 57, widx: 512, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 422 (written: 16928, read: 16506)
      [os_driver-1] buffer active items: 423 (ridx: 121, widx: 543, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 388 (written: 16958, read: 16570)
      [os_driver-1] buffer active items: 389 (ridx: 185, widx: 574, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 361 (written: 16995, read: 16634)
      [os_driver-1] buffer active items: 362 (ridx: 249, widx: 610, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 329 (written: 17027, read: 16698)
      [os_driver-1] buffer active items: 331 (ridx: 313, widx: 643, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 296 (written: 17058, read: 16762)
      [os_driver-1] buffer active items: 297 (ridx: 377, widx: 673, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 263 (written: 17089, read: 16826)
      [os_driver-1] buffer active items: 264 (ridx: 441, widx: 704, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 229 (written: 17119, read: 16890)
      [os_driver-1] buffer active items: 230 (ridx: 505, widx: 734, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 196 (written: 17150, read: 16954)
      [os_driver-1] buffer active items: 197 (ridx: 569, widx: 765, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 159 (written: 17177, read: 17018)
      [os_driver-1] buffer active items: 160 (ridx: 633, widx: 792, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 123 (written: 17205, read: 17082)
      [os_driver-1] buffer active items: 124 (ridx: 697, widx: 820, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 90 (written: 17236, read: 17146)
      [os_driver-1] buffer active items: 91 (ridx: 761, widx: 851, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 54 (written: 17264, read: 17210)
      [os_driver-1] buffer active items: 55 (ridx: 825, widx: 879, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 17300, read: 17274)
      [os_driver-1] buffer active items: 27 (ridx: 889, widx: 915, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 17363, read: 17338)
      [os_driver-1] buffer active items: 26 (ridx: 953, widx: 978, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 17428, read: 17402)
      [os_driver-1] buffer active items: 27 (ridx: 1017, widx: 19, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 17491, read: 17466)
      [os_driver-1] buffer active items: 26 (ridx: 57, widx: 82, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 26 (written: 17556, read: 17530)
      [os_driver-1] buffer active items: 27 (ridx: 121, widx: 147, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 25 (written: 17619, read: 17594)
      [os_driver-1] buffer active items: 26 (ridx: 185, widx: 210, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 17657, read: 17656)
      [os_driver-1] buffer active items: 2 (ridx: 247, widx: 248, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 17687, read: 17658)
      [os_driver-1] buffer active items: 30 (ridx: 249, widx: 278, full: 0, empty: 0)
      
      write_nonblock + read_nonblock
      new_ouster_ros_recovery_wn_rn.mp4
      [os_driver-1] unprocessed packets: 1022 (written: 6370, read: 5348)
      [os_driver-1] buffer active items: 1023 (ridx: 227, widx: 226, full: 0, empty: 0)
      [os_driver-1] [1709740368450491600] missing 12 packets (last m_id: 751, new m_id: 944, time diff:     442129 ns)
      [os_driver-1] unprocessed packets: 1008 (written: 6411, read: 5403)
      [os_driver-1] buffer active items: 1009 (ridx: 282, widx: 266, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 988 (written: 6440, read: 5452)
      [os_driver-1] buffer active items: 989 (ridx: 331, widx: 295, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1001 (written: 6472, read: 5471)
      [os_driver-1] buffer active items: 1002 (ridx: 350, widx: 327, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 996 (written: 6501, read: 5505)
      [os_driver-1] buffer active items: 997 (ridx: 384, widx: 356, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 998 (written: 6530, read: 5532)
      [os_driver-1] buffer active items: 999 (ridx: 411, widx: 385, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 998 (written: 6558, read: 5560)
      [os_driver-1] buffer active items: 999 (ridx: 439, widx: 413, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 990 (written: 6587, read: 5597)
      [os_driver-1] buffer active items: 991 (ridx: 476, widx: 442, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 979 (written: 6617, read: 5638)
      [os_driver-1] buffer active items: 980 (ridx: 517, widx: 472, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 984 (written: 6648, read: 5664)
      [os_driver-1] buffer active items: 985 (ridx: 543, widx: 503, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 997 (written: 6678, read: 5681)
      [os_driver-1] buffer active items: 998 (ridx: 560, widx: 533, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1001 (written: 6709, read: 5708)
      [os_driver-1] buffer active items: 1002 (ridx: 587, widx: 564, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1014 (written: 6738, read: 5724)
      [os_driver-1] buffer active items: 1015 (ridx: 603, widx: 593, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 985 (written: 6767, read: 5782)
      [os_driver-1] buffer active items: 986 (ridx: 661, widx: 622, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 952 (written: 6798, read: 5846)
      [os_driver-1] buffer active items: 953 (ridx: 725, widx: 653, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 938 (written: 6827, read: 5889)
      [os_driver-1] buffer active items: 939 (ridx: 768, widx: 682, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 931 (written: 6857, read: 5926)
      [os_driver-1] buffer active items: 932 (ridx: 805, widx: 712, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 936 (written: 6886, read: 5950)
      [os_driver-1] buffer active items: 937 (ridx: 829, widx: 741, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 919 (written: 6916, read: 5997)
      [os_driver-1] buffer active items: 920 (ridx: 876, widx: 771, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 903 (written: 6948, read: 6045)
      [os_driver-1] buffer active items: 904 (ridx: 924, widx: 803, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 911 (written: 6978, read: 6067)
      [os_driver-1] buffer active items: 912 (ridx: 946, widx: 833, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 895 (written: 7007, read: 6112)
      [os_driver-1] buffer active items: 896 (ridx: 991, widx: 862, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 912 (written: 7036, read: 6124)
      [os_driver-1] buffer active items: 913 (ridx: 1003, widx: 891, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 898 (written: 7066, read: 6167)
      [os_driver-1] buffer active items: 900 (ridx: 22, widx: 921, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 864 (written: 7095, read: 6231)
      [os_driver-1] buffer active items: 865 (ridx: 86, widx: 950, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 843 (written: 7125, read: 6282)
      [os_driver-1] buffer active items: 844 (ridx: 137, widx: 980, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 818 (written: 7156, read: 6338)
      [os_driver-1] buffer active items: 819 (ridx: 193, widx: 1011, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 798 (written: 7186, read: 6388)
      [os_driver-1] buffer active items: 799 (ridx: 243, widx: 17, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 764 (written: 7216, read: 6452)
      [os_driver-1] buffer active items: 765 (ridx: 307, widx: 47, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 730 (written: 7246, read: 6516)
      [os_driver-1] buffer active items: 731 (ridx: 371, widx: 77, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 698 (written: 7278, read: 6580)
      [os_driver-1] buffer active items: 699 (ridx: 435, widx: 109, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 663 (written: 7307, read: 6644)
      [os_driver-1] buffer active items: 664 (ridx: 499, widx: 138, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 627 (written: 7335, read: 6708)
      [os_driver-1] buffer active items: 628 (ridx: 563, widx: 166, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 593 (written: 7365, read: 6772)
      [os_driver-1] buffer active items: 594 (ridx: 627, widx: 196, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 559 (written: 7395, read: 6836)
      [os_driver-1] buffer active items: 560 (ridx: 691, widx: 226, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 528 (written: 7428, read: 6900)
      [os_driver-1] buffer active items: 529 (ridx: 755, widx: 259, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 494 (written: 7458, read: 6964)
      [os_driver-1] buffer active items: 495 (ridx: 819, widx: 289, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 461 (written: 7489, read: 7028)
      [os_driver-1] buffer active items: 462 (ridx: 883, widx: 320, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 426 (written: 7518, read: 7092)
      [os_driver-1] buffer active items: 427 (ridx: 947, widx: 349, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 392 (written: 7548, read: 7156)
      [os_driver-1] buffer active items: 393 (ridx: 1011, widx: 379, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 359 (written: 7579, read: 7220)
      [os_driver-1] buffer active items: 360 (ridx: 51, widx: 410, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 325 (written: 7609, read: 7284)
      [os_driver-1] buffer active items: 326 (ridx: 115, widx: 440, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 290 (written: 7638, read: 7348)
      [os_driver-1] buffer active items: 291 (ridx: 179, widx: 469, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 260 (written: 7672, read: 7412)
      [os_driver-1] buffer active items: 261 (ridx: 243, widx: 503, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 225 (written: 7701, read: 7476)
      [os_driver-1] buffer active items: 226 (ridx: 307, widx: 532, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 191 (written: 7731, read: 7540)
      [os_driver-1] buffer active items: 192 (ridx: 371, widx: 562, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 157 (written: 7761, read: 7604)
      [os_driver-1] buffer active items: 158 (ridx: 435, widx: 592, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 122 (written: 7790, read: 7668)
      [os_driver-1] buffer active items: 123 (ridx: 499, widx: 621, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 87 (written: 7819, read: 7732)
      [os_driver-1] buffer active items: 88 (ridx: 563, widx: 650, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 55 (written: 7851, read: 7796)
      [os_driver-1] buffer active items: 56 (ridx: 627, widx: 682, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 7889, read: 7860)
      [os_driver-1] buffer active items: 30 (ridx: 691, widx: 720, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7917, read: 7916)
      [os_driver-1] buffer active items: 2 (ridx: 747, widx: 748, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 31 (written: 7955, read: 7924)
      
      write_overwrite + read
      new_ouster_ros_recovery_wo_r.mp4
      [os_driver-1] buffer active items: 1023 (ridx: 43, widx: 442, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9673 (written: 27189, read: 17516)
      [os_driver-1] buffer active items: 1023 (ridx: 107, widx: 564, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9746 (written: 27326, read: 17580)
      [os_driver-1] buffer active items: 1023 (ridx: 171, widx: 701, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9811 (written: 27455, read: 17644)
      [os_driver-1] buffer active items: 1023 (ridx: 235, widx: 830, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9778 (written: 27486, read: 17708)
      [os_driver-1] buffer active items: 990 (ridx: 299, widx: 861, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9745 (written: 27517, read: 17772)
      [os_driver-1] buffer active items: 957 (ridx: 363, widx: 892, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9716 (written: 27552, read: 17836)
      [os_driver-1] buffer active items: 928 (ridx: 427, widx: 927, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9682 (written: 27582, read: 17900)
      [os_driver-1] buffer active items: 894 (ridx: 491, widx: 957, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9649 (written: 27613, read: 17964)
      [os_driver-1] buffer active items: 861 (ridx: 555, widx: 988, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9620 (written: 27648, read: 18028)
      [os_driver-1] buffer active items: 832 (ridx: 619, widx: 1023, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9588 (written: 27680, read: 18092)
      [os_driver-1] buffer active items: 800 (ridx: 683, widx: 31, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9558 (written: 27714, read: 18156)
      [os_driver-1] buffer active items: 770 (ridx: 747, widx: 65, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9527 (written: 27747, read: 18220)
      [os_driver-1] buffer active items: 739 (ridx: 811, widx: 98, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9492 (written: 27776, read: 18284)
      [os_driver-1] buffer active items: 704 (ridx: 875, widx: 127, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9463 (written: 27811, read: 18348)
      [os_driver-1] buffer active items: 675 (ridx: 939, widx: 162, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9429 (written: 27841, read: 18412)
      [os_driver-1] buffer active items: 641 (ridx: 1003, widx: 192, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9394 (written: 27870, read: 18476)
      [os_driver-1] buffer active items: 606 (ridx: 43, widx: 221, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9359 (written: 27899, read: 18540)
      [os_driver-1] buffer active items: 571 (ridx: 107, widx: 250, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9328 (written: 27932, read: 18604)
      [os_driver-1] buffer active items: 540 (ridx: 171, widx: 283, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9294 (written: 27962, read: 18668)
      [os_driver-1] buffer active items: 506 (ridx: 235, widx: 313, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9259 (written: 27991, read: 18732)
      [os_driver-1] buffer active items: 471 (ridx: 299, widx: 342, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9245 (written: 28041, read: 18796)
      [os_driver-1] buffer active items: 457 (ridx: 363, widx: 392, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9216 (written: 28067, read: 18851)
      [os_driver-1] buffer active items: 429 (ridx: 418, widx: 419, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9249 (written: 28109, read: 18860)
      [os_driver-1] buffer active items: 461 (ridx: 427, widx: 460, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9216 (written: 28135, read: 18918)
      [os_driver-1] buffer active items: 429 (ridx: 485, widx: 486, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9244 (written: 28168, read: 18924)
      [os_driver-1] buffer active items: 456 (ridx: 491, widx: 519, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 9216 (written: 28193, read: 18977)
      [os_driver-1] buffer active items: 429 (ridx: 544, widx: 545, full: 0, empty: 0)
      
      write_overwrite + read_nonblock
      new_ouster_ros_recovery_wo_rn.mp4
      [os_driver-1] unprocessed packets: 6726 (written: 14171, read: 7445)
      [os_driver-1] buffer active items: 1024 (ridx: 276, widx: 859, full: 1, empty: 0)
      [os_driver-1] unprocessed packets: 6793 (written: 14302, read: 7509)
      [os_driver-1] buffer active items: 1024 (ridx: 340, widx: 990, full: 1, empty: 0)
      [os_driver-1] unprocessed packets: 6854 (written: 14427, read: 7573)
      [os_driver-1] buffer active items: 1023 (ridx: 404, widx: 90, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6820 (written: 14457, read: 7637)
      [os_driver-1] buffer active items: 989 (ridx: 468, widx: 120, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6783 (written: 14484, read: 7701)
      [os_driver-1] buffer active items: 952 (ridx: 532, widx: 147, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6748 (written: 14513, read: 7765)
      [os_driver-1] buffer active items: 917 (ridx: 596, widx: 176, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6712 (written: 14541, read: 7829)
      [os_driver-1] buffer active items: 881 (ridx: 660, widx: 204, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6674 (written: 14567, read: 7893)
      [os_driver-1] buffer active items: 843 (ridx: 724, widx: 230, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6638 (written: 14595, read: 7957)
      [os_driver-1] buffer active items: 807 (ridx: 788, widx: 258, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6602 (written: 14623, read: 8021)
      [os_driver-1] buffer active items: 771 (ridx: 852, widx: 286, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6566 (written: 14651, read: 8085)
      [os_driver-1] buffer active items: 735 (ridx: 916, widx: 314, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6531 (written: 14680, read: 8149)
      [os_driver-1] buffer active items: 700 (ridx: 980, widx: 343, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6496 (written: 14709, read: 8213)
      [os_driver-1] buffer active items: 665 (ridx: 20, widx: 372, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6463 (written: 14740, read: 8277)
      [os_driver-1] buffer active items: 632 (ridx: 84, widx: 403, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6431 (written: 14772, read: 8341)
      [os_driver-1] buffer active items: 600 (ridx: 148, widx: 435, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6399 (written: 14804, read: 8405)
      [os_driver-1] buffer active items: 568 (ridx: 212, widx: 467, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6365 (written: 14834, read: 8469)
      [os_driver-1] buffer active items: 534 (ridx: 276, widx: 497, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6333 (written: 14866, read: 8533)
      [os_driver-1] buffer active items: 502 (ridx: 340, widx: 529, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6300 (written: 14897, read: 8597)
      [os_driver-1] buffer active items: 469 (ridx: 404, widx: 560, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6266 (written: 14927, read: 8661)
      [os_driver-1] buffer active items: 435 (ridx: 468, widx: 590, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6231 (written: 14956, read: 8725)
      [os_driver-1] buffer active items: 400 (ridx: 532, widx: 619, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6213 (written: 15002, read: 8789)
      [os_driver-1] buffer active items: 382 (ridx: 596, widx: 665, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6179 (written: 15032, read: 8853)
      [os_driver-1] buffer active items: 348 (ridx: 660, widx: 695, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6144 (written: 15057, read: 8913)
      [os_driver-1] buffer active items: 314 (ridx: 720, widx: 721, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6173 (written: 15090, read: 8917)
      [os_driver-1] buffer active items: 342 (ridx: 724, widx: 753, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6144 (written: 15116, read: 8972)
      [os_driver-1] buffer active items: 314 (ridx: 779, widx: 780, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6173 (written: 15154, read: 8981)
      [os_driver-1] buffer active items: 342 (ridx: 788, widx: 817, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6144 (written: 15180, read: 9036)
      [os_driver-1] buffer active items: 314 (ridx: 843, widx: 844, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 6172 (written: 15217, read: 9045)
      [os_driver-1] buffer active items: 341 (ridx: 852, widx: 880, full: 0, empty: 0)
      
      write + read
      new_ouster_ros_recovery_w_r.mp4
      [os_driver-1] unprocessed packets: 1022 (written: 5152, read: 4130)
      [os_driver-1] buffer active items: 1023 (ridx: 33, widx: 32, full: 0, empty: 0)
      [os_driver-1] [1709742462215625332] missing 16 packets (last m_id: 127, new m_id: 384, time diff:     400620 ns)
      [os_driver-1] unprocessed packets: 1022 (written: 5184, read: 4162)
      [os_driver-1] buffer active items: 1023 (ridx: 65, widx: 64, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1002 (written: 5227, read: 4225)
      [os_driver-1] buffer active items: 1003 (ridx: 128, widx: 106, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 968 (written: 5257, read: 4289)
      [os_driver-1] buffer active items: 969 (ridx: 192, widx: 136, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 934 (written: 5287, read: 4353)
      [os_driver-1] buffer active items: 935 (ridx: 256, widx: 166, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 923 (written: 5317, read: 4394)
      [os_driver-1] buffer active items: 924 (ridx: 297, widx: 196, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 919 (written: 5343, read: 4424)
      [os_driver-1] buffer active items: 920 (ridx: 327, widx: 222, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 885 (written: 5368, read: 4483)
      [os_driver-1] buffer active items: 886 (ridx: 386, widx: 247, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 867 (written: 5395, read: 4528)
      [os_driver-1] buffer active items: 868 (ridx: 431, widx: 274, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 839 (written: 5422, read: 4583)
      [os_driver-1] buffer active items: 840 (ridx: 486, widx: 301, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 809 (written: 5452, read: 4643)
      [os_driver-1] buffer active items: 810 (ridx: 546, widx: 331, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 773 (written: 5480, read: 4707)
      [os_driver-1] buffer active items: 774 (ridx: 610, widx: 359, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 745 (written: 5516, read: 4771)
      [os_driver-1] buffer active items: 746 (ridx: 674, widx: 395, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 732 (written: 5550, read: 4818)
      [os_driver-1] buffer active items: 733 (ridx: 721, widx: 429, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 730 (written: 5582, read: 4852)
      [os_driver-1] buffer active items: 731 (ridx: 755, widx: 461, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 693 (written: 5609, read: 4916)
      [os_driver-1] buffer active items: 694 (ridx: 819, widx: 488, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 683 (written: 5638, read: 4955)
      [os_driver-1] buffer active items: 684 (ridx: 858, widx: 517, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 668 (written: 5667, read: 4999)
      [os_driver-1] buffer active items: 669 (ridx: 902, widx: 546, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 679 (written: 5700, read: 5021)
      [os_driver-1] buffer active items: 680 (ridx: 924, widx: 579, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 669 (written: 5729, read: 5060)
      [os_driver-1] buffer active items: 670 (ridx: 963, widx: 608, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 675 (written: 5758, read: 5083)
      [os_driver-1] buffer active items: 676 (ridx: 986, widx: 637, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 683 (written: 5788, read: 5105)
      [os_driver-1] buffer active items: 684 (ridx: 1008, widx: 667, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 662 (written: 5819, read: 5157)
      [os_driver-1] buffer active items: 663 (ridx: 36, widx: 698, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 645 (written: 5850, read: 5205)
      [os_driver-1] buffer active items: 646 (ridx: 84, widx: 729, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 610 (written: 5879, read: 5269)
      [os_driver-1] buffer active items: 611 (ridx: 148, widx: 758, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 575 (written: 5908, read: 5333)
      [os_driver-1] buffer active items: 576 (ridx: 212, widx: 787, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 546 (written: 5943, read: 5397)
      [os_driver-1] buffer active items: 547 (ridx: 276, widx: 822, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 512 (written: 5973, read: 5461)
      [os_driver-1] buffer active items: 513 (ridx: 340, widx: 852, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 478 (written: 6003, read: 5525)
      [os_driver-1] buffer active items: 479 (ridx: 404, widx: 882, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 444 (written: 6033, read: 5589)
      [os_driver-1] buffer active items: 445 (ridx: 468, widx: 912, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 411 (written: 6064, read: 5653)
      [os_driver-1] buffer active items: 412 (ridx: 532, widx: 943, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 378 (written: 6095, read: 5717)
      [os_driver-1] buffer active items: 379 (ridx: 596, widx: 974, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 344 (written: 6125, read: 5781)
      [os_driver-1] buffer active items: 345 (ridx: 660, widx: 1004, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 310 (written: 6155, read: 5845)
      [os_driver-1] buffer active items: 311 (ridx: 724, widx: 10, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 280 (written: 6189, read: 5909)
      [os_driver-1] buffer active items: 281 (ridx: 788, widx: 44, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 247 (written: 6220, read: 5973)
      [os_driver-1] buffer active items: 248 (ridx: 852, widx: 75, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 213 (written: 6250, read: 6037)
      [os_driver-1] buffer active items: 214 (ridx: 916, widx: 105, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 178 (written: 6279, read: 6101)
      [os_driver-1] buffer active items: 179 (ridx: 980, widx: 134, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 146 (written: 6311, read: 6165)
      [os_driver-1] buffer active items: 147 (ridx: 20, widx: 166, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 112 (written: 6341, read: 6229)
      [os_driver-1] buffer active items: 113 (ridx: 84, widx: 196, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 78 (written: 6371, read: 6293)
      [os_driver-1] buffer active items: 79 (ridx: 148, widx: 226, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 43 (written: 6400, read: 6357)
      [os_driver-1] buffer active items: 44 (ridx: 212, widx: 255, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 32 (written: 6453, read: 6421)
      [os_driver-1] buffer active items: 33 (ridx: 276, widx: 308, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 6514, read: 6485)
      [os_driver-1] buffer active items: 30 (ridx: 340, widx: 369, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 6578, read: 6549)
      [os_driver-1] buffer active items: 30 (ridx: 404, widx: 433, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 6640, read: 6613)
      [os_driver-1] buffer active items: 28 (ridx: 468, widx: 495, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 6705, read: 6677)
      [os_driver-1] buffer active items: 29 (ridx: 532, widx: 560, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 6770, read: 6741)
      [os_driver-1] buffer active items: 30 (ridx: 596, widx: 625, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 6834, read: 6805)
      [os_driver-1] buffer active items: 30 (ridx: 660, widx: 689, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 6897, read: 6869)
      [os_driver-1] buffer active items: 29 (ridx: 724, widx: 752, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 33 (written: 6966, read: 6933)
      [os_driver-1] buffer active items: 34 (ridx: 788, widx: 821, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 7026, read: 6997)
      [os_driver-1] buffer active items: 30 (ridx: 852, widx: 881, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 7089, read: 7061)
      [os_driver-1] buffer active items: 29 (ridx: 916, widx: 944, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 30 (written: 7155, read: 7125)
      [os_driver-1] buffer active items: 31 (ridx: 980, widx: 1010, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 7188, read: 7187)
      [os_driver-1] buffer active items: 2 (ridx: 18, widx: 19, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 7216, read: 7189)
      [os_driver-1] buffer active items: 28 (ridx: 20, widx: 47, full: 0, empty: 0)
      
      write + read_nonblock
      new_ouster_ros_recovery_w_rn.mp4
      [os_driver-1] unprocessed packets: 1022 (written: 6499, read: 5477)
      [os_driver-1] buffer active items: 1023 (ridx: 356, widx: 355, full: 0, empty: 0)
      [os_driver-1] [1709742991887370047] missing 25 packets (last m_id: 191, new m_id: 592, time diff:      39925 ns)
      [os_driver-1] [1709742991887650770] missing 22 packets (last m_id: 111, new m_id: 464, time diff:       7274 ns)
      [os_driver-1] unprocessed packets: 1015 (written: 6540, read: 5525)
      [os_driver-1] buffer active items: 1016 (ridx: 404, widx: 395, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1022 (written: 6566, read: 5544)
      [os_driver-1] buffer active items: 1024 (ridx: 423, widx: 422, full: 1, empty: 0)
      [os_driver-1] unprocessed packets: 1006 (written: 6597, read: 5591)
      [os_driver-1] buffer active items: 1007 (ridx: 470, widx: 452, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1009 (written: 6627, read: 5618)
      [os_driver-1] buffer active items: 1010 (ridx: 497, widx: 482, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1003 (written: 6656, read: 5653)
      [os_driver-1] buffer active items: 1004 (ridx: 532, widx: 511, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1020 (written: 6687, read: 5667)
      [os_driver-1] buffer active items: 1021 (ridx: 546, widx: 542, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1003 (written: 6717, read: 5714)
      [os_driver-1] buffer active items: 1004 (ridx: 593, widx: 572, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 992 (written: 6747, read: 5755)
      [os_driver-1] buffer active items: 993 (ridx: 634, widx: 602, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 965 (written: 6776, read: 5811)
      [os_driver-1] buffer active items: 966 (ridx: 690, widx: 631, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 958 (written: 6806, read: 5848)
      [os_driver-1] buffer active items: 959 (ridx: 727, widx: 661, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 939 (written: 6834, read: 5895)
      [os_driver-1] buffer active items: 940 (ridx: 774, widx: 689, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 921 (written: 6864, read: 5943)
      [os_driver-1] buffer active items: 922 (ridx: 822, widx: 719, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 916 (written: 6895, read: 5979)
      [os_driver-1] buffer active items: 917 (ridx: 858, widx: 750, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 908 (written: 6932, read: 6024)
      [os_driver-1] buffer active items: 909 (ridx: 903, widx: 787, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 917 (written: 6964, read: 6047)
      [os_driver-1] buffer active items: 918 (ridx: 926, widx: 819, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 898 (written: 6996, read: 6098)
      [os_driver-1] buffer active items: 899 (ridx: 977, widx: 851, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 897 (written: 7028, read: 6131)
      [os_driver-1] buffer active items: 898 (ridx: 1010, widx: 883, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 890 (written: 7058, read: 6168)
      [os_driver-1] buffer active items: 891 (ridx: 23, widx: 913, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 891 (written: 7090, read: 6199)
      [os_driver-1] buffer active items: 892 (ridx: 54, widx: 945, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 870 (written: 7120, read: 6250)
      [os_driver-1] buffer active items: 871 (ridx: 105, widx: 975, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 862 (written: 7153, read: 6291)
      [os_driver-1] buffer active items: 863 (ridx: 146, widx: 1008, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 872 (written: 7185, read: 6313)
      [os_driver-1] buffer active items: 873 (ridx: 168, widx: 16, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 894 (written: 7215, read: 6321)
      [os_driver-1] buffer active items: 895 (ridx: 176, widx: 46, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 866 (written: 7246, read: 6380)
      [os_driver-1] buffer active items: 867 (ridx: 235, widx: 77, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 850 (written: 7278, read: 6428)
      [os_driver-1] buffer active items: 851 (ridx: 283, widx: 109, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 859 (written: 7310, read: 6451)
      [os_driver-1] buffer active items: 860 (ridx: 306, widx: 141, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 844 (written: 7340, read: 6496)
      [os_driver-1] buffer active items: 845 (ridx: 351, widx: 171, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 866 (written: 7371, read: 6505)
      [os_driver-1] buffer active items: 867 (ridx: 360, widx: 202, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 858 (written: 7404, read: 6546)
      [os_driver-1] buffer active items: 859 (ridx: 401, widx: 235, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 831 (written: 7441, read: 6610)
      [os_driver-1] buffer active items: 832 (ridx: 465, widx: 272, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 800 (written: 7474, read: 6674)
      [os_driver-1] buffer active items: 801 (ridx: 529, widx: 305, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 767 (written: 7505, read: 6738)
      [os_driver-1] buffer active items: 769 (ridx: 593, widx: 337, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 732 (written: 7534, read: 6802)
      [os_driver-1] buffer active items: 733 (ridx: 657, widx: 365, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 700 (written: 7566, read: 6866)
      [os_driver-1] buffer active items: 701 (ridx: 721, widx: 397, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 665 (written: 7595, read: 6930)
      [os_driver-1] buffer active items: 666 (ridx: 785, widx: 426, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 630 (written: 7624, read: 6994)
      [os_driver-1] buffer active items: 631 (ridx: 849, widx: 455, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 597 (written: 7655, read: 7058)
      [os_driver-1] buffer active items: 598 (ridx: 913, widx: 486, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 567 (written: 7689, read: 7122)
      [os_driver-1] buffer active items: 568 (ridx: 977, widx: 520, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 532 (written: 7718, read: 7186)
      [os_driver-1] buffer active items: 533 (ridx: 17, widx: 549, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 499 (written: 7749, read: 7250)
      [os_driver-1] buffer active items: 500 (ridx: 81, widx: 580, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 464 (written: 7778, read: 7314)
      [os_driver-1] buffer active items: 465 (ridx: 145, widx: 609, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 430 (written: 7808, read: 7378)
      [os_driver-1] buffer active items: 431 (ridx: 209, widx: 639, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 396 (written: 7838, read: 7442)
      [os_driver-1] buffer active items: 397 (ridx: 273, widx: 669, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 362 (written: 7868, read: 7506)
      [os_driver-1] buffer active items: 363 (ridx: 337, widx: 699, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 327 (written: 7897, read: 7570)
      [os_driver-1] buffer active items: 328 (ridx: 401, widx: 728, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 298 (written: 7932, read: 7634)
      [os_driver-1] buffer active items: 299 (ridx: 465, widx: 763, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 263 (written: 7961, read: 7698)
      [os_driver-1] buffer active items: 264 (ridx: 529, widx: 792, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 228 (written: 7990, read: 7762)
      [os_driver-1] buffer active items: 229 (ridx: 593, widx: 821, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 195 (written: 8021, read: 7826)
      [os_driver-1] buffer active items: 196 (ridx: 657, widx: 852, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 160 (written: 8050, read: 7890)
      [os_driver-1] buffer active items: 161 (ridx: 721, widx: 882, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 126 (written: 8080, read: 7954)
      [os_driver-1] buffer active items: 127 (ridx: 785, widx: 911, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 93 (written: 8111, read: 8018)
      [os_driver-1] buffer active items: 94 (ridx: 849, widx: 942, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 60 (written: 8142, read: 8082)
      [os_driver-1] buffer active items: 61 (ridx: 913, widx: 973, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 32 (written: 8178, read: 8146)
      [os_driver-1] buffer active items: 33 (ridx: 977, widx: 1009, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8238, read: 8210)
      [os_driver-1] buffer active items: 29 (ridx: 17, widx: 45, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8302, read: 8274)
      [os_driver-1] buffer active items: 29 (ridx: 81, widx: 109, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 8367, read: 8338)
      [os_driver-1] buffer active items: 30 (ridx: 145, widx: 174, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8430, read: 8402)
      [os_driver-1] buffer active items: 29 (ridx: 209, widx: 237, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8494, read: 8466)
      [os_driver-1] buffer active items: 29 (ridx: 273, widx: 301, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8558, read: 8530)
      [os_driver-1] buffer active items: 29 (ridx: 337, widx: 365, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 29 (written: 8623, read: 8594)
      [os_driver-1] buffer active items: 30 (ridx: 401, widx: 430, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 31 (written: 8689, read: 8658)
      [os_driver-1] buffer active items: 32 (ridx: 465, widx: 496, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8750, read: 8722)
      [os_driver-1] buffer active items: 29 (ridx: 529, widx: 557, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 8814, read: 8786)
      [os_driver-1] buffer active items: 29 (ridx: 593, widx: 621, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 8877, read: 8850)
      [os_driver-1] buffer active items: 28 (ridx: 657, widx: 684, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 27 (written: 8941, read: 8914)
      [os_driver-1] buffer active items: 28 (ridx: 721, widx: 748, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 1 (written: 8975, read: 8974)
      [os_driver-1] buffer active items: 2 (ridx: 781, widx: 782, full: 0, empty: 0)
      [os_driver-1] unprocessed packets: 28 (written: 9006, read: 8978)
      [os_driver-1] buffer active items: 29 (ridx: 785, widx: 813, full: 0, empty: 0)
      

I currently have all the debug printing separate in a devel branch. I'm not sure if it would be useful to have something similar in the driver. The read/write counting and buffer status reports could be done at the driver level. However, the packet id counting would make more sense directly from the SDK in ScanBatcher, since it would be boilerplating the same loops from the batcher.

Final remarks

This refactor remedies the issue with the reader holding a lock on the buffer for the whole processing duration and instead allows the writer to continue filling the buffer, so we don't end up with missing lidar chunks under normal operation. However, when the processing time of the reader does get too high (for ex. with more subscribers), the buffer will eventually overfill and this will still cause less than ideal states. Simply increasing the buffer size is probably not a viable solution since the rate of filling is non-zero and the buffer would overfill eventually either way.

So the second half of the problem - preventing the buffer from getting overfilled - still needs to be solved.

  • Further separating out the data processing from buffer reading into its own thread, and using another ringbuffer abstraction there?

I've also done some quick CPU load tests. I am only measuring the total CPU usage with the top command while the node was running, so it is by no means a precise profiling and will contain the node usage plus any background processes. Values are averaged from 50 measurements at one measurement per second. The background usage (averaged from 100 measurements) without the node running was around 2 (+- 1) %.

ros2_ouster (community)

ros2_ouster

ouster_ros (this new)

new_ouster_ros

ouster_ros (this old)

old_ouster_ros

There does appear to be more CPU usage with the new ringbuffer. I But I think it does make sense, since with this implementation, the threads should be spending more time doing work and less time waiting.

Finally, I performed a direct refactor of the ThreadSafeRingBuffer class here, but maybe it would be better to have this separate as its own class, something like LockFreeRingBuffer? In case it's necessary to switch between the two implementations or use each for different purposes.

@Imaniac230 Imaniac230 force-pushed the ros2-foxy-missing-lidar-chunk-fix-prfinal branch from ad556dd to 455aff2 Compare March 6, 2024 19:39
@Imaniac230 Imaniac230 marked this pull request as ready for review March 6, 2024 20:01
@Imaniac230
Copy link
Author

I see that this thing has been quiet for some time now. Just checking in, @Samahu are there any further remarks or changes to be made?

@Samahu
Copy link
Contributor

Samahu commented Apr 5, 2024

Hi @Imaniac230, sorry I was busy with other tasks. I am taking a look today.

@Samahu
Copy link
Contributor

Samahu commented Apr 7, 2024

@Imaniac230 I am still evaluating your contribution, given the complexity of your solution I need a little more time before committing. Please note that I have been working on a solution that addresses the problem differently, you can view the prototype for ROS1 here, note it is still a work in progress in that I didn't get to fully replace the existing ThreadSafeRingBuffer yet. I will compare the performance of the two solution and let you know of my decision. Thanks for your patience.

@Imaniac230
Copy link
Author

Sure, I'll be looking forward to your thoughts.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants