Skip to content

Commit

Permalink
Fix PCL KDTree empty cloud exception
Browse files Browse the repository at this point in the history
  • Loading branch information
charlescochran committed May 23, 2024
1 parent 3f83d32 commit 116eaf5
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion src/lio/Estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -927,7 +927,9 @@ void Estimator::Estimate(std::list<LidarFrame>& lidarFrameList,
Eigen::Vector3d exPbl = -1.0 * exRbl * exTlb.topRightCorner(3,1);
kdtreeCornerFromLocal->setInputCloud(laserCloudCornerFromLocal);
kdtreeSurfFromLocal->setInputCloud(laserCloudSurfFromLocal);
kdtreeNonFeatureFromLocal->setInputCloud(laserCloudNonFeatureFromLocal);
if(!laserCloudNonFeatureFromLocal->empty()) {
kdtreeNonFeatureFromLocal->setInputCloud(laserCloudNonFeatureFromLocal);
}

std::unique_lock<std::mutex> locker3(map_manager->mtx_MapManager);
for(int i = 0; i < 4851; i++){
Expand Down

0 comments on commit 116eaf5

Please sign in to comment.