From b6ff7d1c8b210a96b74e919823771e1e32249758 Mon Sep 17 00:00:00 2001 From: "marvin.li" Date: Wed, 29 Nov 2023 10:31:01 +0800 Subject: [PATCH] optimize framing performance --- CHANGELOG.md | 4 ++++ README.md | 4 ++++ src/comm/pub_handler.cpp | 3 --- 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 8abe0d1..df75257 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -2,6 +2,10 @@ All notable changes to this project will be documented in this file. +## [1.2.4] +### Fixed +- Optimize framing performance + ## [1.2.3] ### Fixed - Optimize framing logic and reduce CPU usage diff --git a/README.md b/README.md index a625d83..bbfacb7 100644 --- a/README.md +++ b/README.md @@ -2,6 +2,10 @@ Livox ROS Driver 2 is the 2nd-generation driver package used to connect LiDAR products produced by Livox, applicable for ROS (noetic recommended) and ROS2 (foxy or humble recommended). + **Note :** + + As a debugging tool, Livox ROS Driver is not recommended for mass production but limited to test scenarios. You should optimize the code based on the original source to meet your various needs. + ## 1. Preparation ### 1.1 OS requirements diff --git a/src/comm/pub_handler.cpp b/src/comm/pub_handler.cpp index 4c13dc4..07d4d4f 100644 --- a/src/comm/pub_handler.cpp +++ b/src/comm/pub_handler.cpp @@ -239,9 +239,6 @@ void PubHandler::RawDataProcess() { } raw_data = raw_packet_queue_.front(); raw_packet_queue_.pop_front(); - if (raw_packet_queue_.size() < 3) { // reduce CPU usage - std::this_thread::sleep_for(std::chrono::microseconds(50)); - } } uint32_t id = 0; GetLidarId(raw_data.lidar_type, raw_data.handle, id);