Skip to content

Commit

Permalink
Removed unused include and comments
Browse files Browse the repository at this point in the history
Signed-off-by: anhnv3991 <[email protected]>
  • Loading branch information
anhnv3991 committed Mar 25, 2024
1 parent a96602a commit 576c994
Showing 1 changed file with 2 additions and 5 deletions.
7 changes: 2 additions & 5 deletions include/multigrid_pclomp/multi_voxel_grid_covariance_omp.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,10 +66,6 @@
#include <ctime>
#include <fstream>
#include <sstream>
#include <sys/time.h>
#include <pcl/io/pcd_io.h>
#include <queue>
#include <unistd.h>

namespace pclomp {
/** \brief A searchable voxel structure containing the mean and covariance of the data.
Expand Down Expand Up @@ -315,6 +311,8 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT> {
std::vector<std::string> getCurrentMapIDs() const;

void setThreadNum(int thread_num) {
sync();

if(thread_num <= 0) {
thread_num_ = 1;
}
Expand All @@ -338,7 +336,6 @@ class MultiVoxelGridCovariance : public pcl::VoxelGrid<PointT> {

// Loop until an idle thread is found
while(true) {
// gettimeofday(&start, NULL);
// Return immediately if a thread that has not been given a job is found
if(!thread_futs_[tid].valid()) {
last_check_tid_ = tid;
Expand Down

0 comments on commit 576c994

Please sign in to comment.