Livox-SDK / LIO-Livox

A Robust LiDAR-Inertial Odometry for Livox LiDAR
BSD 3-Clause "New" or "Revised" License
633 stars 162 forks source link

Delays #77

Open PanterSoft opened 3 months ago

PanterSoft commented 3 months ago

Hello,

Quick question did anyone get this running in pretty much Real Time ? for me if I play a scene of abaout 300 seconds I get a delay of about 100 seconds. Is there a Setting to skip some frames to get rid of the delay or reduce it ?

Thanks for this amazing Project

charlescochran commented 2 months ago

It's probably hitting a CPU limit from what I've seen. When the sensor isn't moving (and thus the solver isn't having to do much), I can get it to just about keep up. But it quickly gets overwhelmed if it has to do much tracking. The reason it gets "behind" because it is buffering messages in a FIFO (like you are speculating), which doesn't seem like a good idea! Unfortunately, there's no setting to disable this, but I made some code changes to bypass the FIFO and it is able to "keep up" now (it still drops frames when the sensor is moving, but the odometry works fairly well). I am considering opening a PR with this change (and others), but I'm not sure if @Livox-SDK would be open to taking it.

PanterSoft commented 2 months ago

Okay That sounds like what I expected. Do You have a fork which I can maybe try out ? @charlescochran

charlescochran commented 2 months ago

I ended up leaving this change out of my PR because it's rather messy (I'm just clearing out the lidar message queue instead of popping from it; a proper fix would be get rid of the queue entirely). That being said, you can replicate my quick-fix by applying this diff in PoseEstimation.cpp's process() function:

     if(!_lidarMsgQueue.empty()){
-      // get new lidar msg
-      time_curr_lidar = _lidarMsgQueue.front()->header.stamp.toSec();
-      pcl::fromROSMsg(*_lidarMsgQueue.front(), *laserCloudFullRes);
-      _lidarMsgQueue.pop();
+      // instead of queuing, just use the latest scan and throw away the old ones!
+      time_curr_lidar = _lidarMsgQueue.back()->header.stamp.toSec();
+      pcl::fromROSMsg(*_lidarMsgQueue.back(), *laserCloudFullRes);
+      _lidarMsgQueue = {};
       newfullCloud = true;
     }

That should be all you need to do.