diff --git a/CAPE/CAPE/run_cape_offline.cpp b/CAPE/CAPE/run_cape_offline.cpp index 54d3ec7d..06d46888 100644 --- a/CAPE/CAPE/run_cape_offline.cpp +++ b/CAPE/CAPE/run_cape_offline.cpp @@ -244,7 +244,10 @@ int main(int argc, char ** argv){ double t2 = cv::getTickCount(); double time_elapsed = (t2-t1)/(double)cv::getTickFrequency(); cout<<"Total time elapsed: "< #include +#include #include #include #include @@ -57,8 +58,15 @@ int main() { auto * depth = new depthBuffer_t(); read_pcd(*points); ddpff->setBuffers(points, colors, depth); - + clock_t start = clock(); ddpff->compute(); + clock_t stop = clock(); + std::ofstream ex_time; + + ex_time.open ("output/ex_time.txt"); + ex_time << "Elapsed(ms)=" << (double)(stop - start)/(CLOCKS_PER_SEC/1000) << std::endl; + ex_time.close(); + const std::vector & result = ddpff->getPlanes(); for (const auto& plane : result) { std::cout << "Plane with " << plane.count << " points detected!" << std::endl; diff --git a/DDPFF/scripts/build_cloud_from_planes.py b/DDPFF/scripts/build_cloud_from_planes.py index 20af84c5..3eb1d3cc 100644 --- a/DDPFF/scripts/build_cloud_from_planes.py +++ b/DDPFF/scripts/build_cloud_from_planes.py @@ -40,4 +40,5 @@ os.mkdir(folder_path) np.save(os.path.join(folder_path, "{}.npy".format(filename)), labels) + os.replace("output/ex_time.txt", os.path.join(folder_path,"ex_time.txt")) o3d.io.write_point_cloud(os.path.join(folder_path, "{}.pcd".format(filename)), pcd) diff --git a/PCL_ConnectedComponents/main.cpp b/PCL_ConnectedComponents/main.cpp index 96d6f72c..e63b5d96 100644 --- a/PCL_ConnectedComponents/main.cpp +++ b/PCL_ConnectedComponents/main.cpp @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -52,9 +53,16 @@ int main(int argc, char** argv) { pcl::PointCloud::Ptr cloud = readPointCloud(pathToRGB.path().string()); ConnectedComponents connectedComponentsAlgorithm(cloud); std::vector clusters; - connectedComponentsAlgorithm.SegmentCloud(clusters); + + double comp_time = connectedComponentsAlgorithm.SegmentCloud(clusters); + writeClustersInDataFolder(pathToRGB.path().string(), cloud, clusters); + + std::ofstream ex_time; + ex_time.open ("./output/" + getFileName(pathToRGB.path().string()) + "/" +"ex_time.txt"); + ex_time << "Elapsed(ms)=" << comp_time << std::endl; + ex_time.close(); } return 0; } \ No newline at end of file diff --git a/PCL_ConnectedComponents/scripts/build_colored_cloud.py b/PCL_ConnectedComponents/scripts/build_colored_cloud.py index a86dad42..71a5bb7b 100644 --- a/PCL_ConnectedComponents/scripts/build_colored_cloud.py +++ b/PCL_ConnectedComponents/scripts/build_colored_cloud.py @@ -7,6 +7,8 @@ def create_colored_cloud(): rootdir = "./input" for file in os.listdir(rootdir): + if "ex_time" in file: + continue file_path = os.path.join(rootdir, file) npy_path = os.path.join("./output", file[:-4], file[:-4] + ".npy") labels = np.load(npy_path) diff --git a/PCL_ConnectedComponents/scripts/save_as_npy.py b/PCL_ConnectedComponents/scripts/save_as_npy.py index cc146651..a985650b 100644 --- a/PCL_ConnectedComponents/scripts/save_as_npy.py +++ b/PCL_ConnectedComponents/scripts/save_as_npy.py @@ -7,6 +7,8 @@ def convert_txt_files_to_npy_format(): for subdir, _, files in os.walk(rootdir): for file in files: + if "ex_time" in file: + continue file_path = os.path.join(subdir, file) labels_array = np.loadtxt(file_path).astype(int) diff --git a/PCL_ConnectedComponents/src/ConnectedComponents.cpp b/PCL_ConnectedComponents/src/ConnectedComponents.cpp index a58246ac..3438cc92 100644 --- a/PCL_ConnectedComponents/src/ConnectedComponents.cpp +++ b/PCL_ConnectedComponents/src/ConnectedComponents.cpp @@ -4,7 +4,7 @@ ConnectedComponents::ConnectedComponents(pcl::PointCloud::Con { } -void ConnectedComponents::SegmentCloud(std::vector& clusters) { +double ConnectedComponents::SegmentCloud(std::vector& clusters) { pcl::PointCloud::Ptr normal_cloud(new pcl::PointCloud); ne_.setInputCloud(cloud); ne_.compute(*normal_cloud); @@ -37,12 +37,15 @@ void ConnectedComponents::SegmentCloud(std::vector& clusters) pcl::OrganizedConnectedComponentSegmentation euclidean_segmentation( euclidean_cluster_comparator_); euclidean_segmentation.setInputCloud(cloud); + clock_t start = clock(); euclidean_segmentation.segment(euclidean_labels, euclidean_label_indices); - + clock_t stop = clock(); for (auto & euclidean_label_indice : euclidean_label_indices) { if (euclidean_label_indice.indices.size() > 1000) { clusters.push_back(euclidean_label_indice); } } + return (double)(stop - start)/(CLOCKS_PER_SEC/1000); } + return 0; } \ No newline at end of file diff --git a/PCL_ConnectedComponents/src/ConnectedComponents.h b/PCL_ConnectedComponents/src/ConnectedComponents.h index de52193f..0723df63 100644 --- a/PCL_ConnectedComponents/src/ConnectedComponents.h +++ b/PCL_ConnectedComponents/src/ConnectedComponents.h @@ -25,5 +25,5 @@ class ConnectedComponents { public: ConnectedComponents(pcl::PointCloud::ConstPtr cloud); - void SegmentCloud(std::vector& clusters); + double SegmentCloud(std::vector& clusters); }; \ No newline at end of file diff --git a/PCL_RegionGrowing/main.cpp b/PCL_RegionGrowing/main.cpp index cf3bef00..fc1c8476 100644 --- a/PCL_RegionGrowing/main.cpp +++ b/PCL_RegionGrowing/main.cpp @@ -1,4 +1,5 @@ #include +#include #include #include #include @@ -56,9 +57,16 @@ int main(int argc, char** argv) { RegionGrowing regionGrowing; std::vector clusters; - regionGrowing.getClusters(cloud, clusters); + + double comp_time = regionGrowing.getClusters(cloud, clusters); + writeClustersInDataFolder(pathToPCD.path().string(), cloud, clusters); + + std::ofstream ex_time; + ex_time.open ("./output/" + getFileName(pathToPCD.path().string()) + "/" +"ex_time.txt"); + ex_time << "Elapsed(ms)=" << comp_time << std::endl; + ex_time.close(); } return 0; diff --git a/PCL_RegionGrowing/scripts/build_colored_cloud.py b/PCL_RegionGrowing/scripts/build_colored_cloud.py index a86dad42..71a5bb7b 100644 --- a/PCL_RegionGrowing/scripts/build_colored_cloud.py +++ b/PCL_RegionGrowing/scripts/build_colored_cloud.py @@ -7,6 +7,8 @@ def create_colored_cloud(): rootdir = "./input" for file in os.listdir(rootdir): + if "ex_time" in file: + continue file_path = os.path.join(rootdir, file) npy_path = os.path.join("./output", file[:-4], file[:-4] + ".npy") labels = np.load(npy_path) diff --git a/PCL_RegionGrowing/scripts/save_as_npy.py b/PCL_RegionGrowing/scripts/save_as_npy.py index cc146651..a985650b 100644 --- a/PCL_RegionGrowing/scripts/save_as_npy.py +++ b/PCL_RegionGrowing/scripts/save_as_npy.py @@ -7,6 +7,8 @@ def convert_txt_files_to_npy_format(): for subdir, _, files in os.walk(rootdir): for file in files: + if "ex_time" in file: + continue file_path = os.path.join(subdir, file) labels_array = np.loadtxt(file_path).astype(int) diff --git a/PCL_RegionGrowing/src/RegionGrowing.cpp b/PCL_RegionGrowing/src/RegionGrowing.cpp index 8e8b2822..041c315b 100644 --- a/PCL_RegionGrowing/src/RegionGrowing.cpp +++ b/PCL_RegionGrowing/src/RegionGrowing.cpp @@ -1,6 +1,6 @@ #include "RegionGrowing.h" -void RegionGrowing::getClusters(pcl::PointCloud::Ptr pointCloud, std::vector& clusters) { +double RegionGrowing::getClusters(pcl::PointCloud::Ptr pointCloud, std::vector& clusters) { pcl::search::Search::Ptr tree(new pcl::search::KdTree); pcl::PointCloud ::Ptr normals(new pcl::PointCloud ); pcl::NormalEstimation normal_estimator; @@ -23,6 +23,8 @@ void RegionGrowing::getClusters(pcl::PointCloud::Ptr pointCloud, reg.setSmoothnessThreshold(3.0 / 180.0 * M_PI); reg.setCurvatureThreshold(1.0); - + clock_t start = clock(); reg.extract(clusters); + clock_t stop = clock(); + return (double)(stop - start)/(CLOCKS_PER_SEC/1000); } diff --git a/PCL_RegionGrowing/src/RegionGrowing.h b/PCL_RegionGrowing/src/RegionGrowing.h index 56ccb48b..56c9a270 100644 --- a/PCL_RegionGrowing/src/RegionGrowing.h +++ b/PCL_RegionGrowing/src/RegionGrowing.h @@ -11,5 +11,5 @@ class RegionGrowing { public: - void getClusters(pcl::PointCloud::Ptr pointCloud, std::vector& clusters); + double getClusters(pcl::PointCloud::Ptr pointCloud, std::vector& clusters); }; diff --git a/STORM-IRIT/app/pdpcComputeMultiScaleFeatures.cpp b/STORM-IRIT/app/pdpcComputeMultiScaleFeatures.cpp index 5a8c0561..65ae5ccd 100644 --- a/STORM-IRIT/app/pdpcComputeMultiScaleFeatures.cpp +++ b/STORM-IRIT/app/pdpcComputeMultiScaleFeatures.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #include #include @@ -40,6 +41,7 @@ int main(int argc, char **argv) if(!ok) return 1; const int point_count = points.size(); + if(!points.has_normals()) { error().iff(in_v) << "Normal vectors are required!"; @@ -47,6 +49,8 @@ int main(int argc, char **argv) } points.build_kdtree(); + + clock_t start = clock(); // 1. Scales --------------------------------------------------------------- info().iff(in_v) << "Computing " << in_scount << " scales"; @@ -188,6 +192,12 @@ int main(int argc, char **argv) } } // for j + clock_t stop = clock(); + std::ofstream ex_time; + ex_time.open ("./output/" + in_output + "/" +"ex_time.txt", std::ios_base::app); + ex_time << "Elapsed(m0)=" << (double)(stop - start)/(CLOCKS_PER_SEC/1000) << std::endl; + ex_time.close(); + features.save(in_output + "_features.txt"); scales.save( in_output + "_scales.txt"); diff --git a/STORM-IRIT/app/pdpcPostProcess.cpp b/STORM-IRIT/app/pdpcPostProcess.cpp index b1dccd4b..91359370 100644 --- a/STORM-IRIT/app/pdpcPostProcess.cpp +++ b/STORM-IRIT/app/pdpcPostProcess.cpp @@ -10,6 +10,14 @@ #include using namespace pdpc; +std::string getFileName(std::string const &s) { + char sep = '/'; + size_t i = s.rfind(sep, s.length()); + if (i != std::string::npos) { + return(s.substr(i+1, s.length() - i - 6)); + } + return(""); +} int main(int argc, char **argv) { @@ -30,6 +38,10 @@ int main(int argc, char **argv) bool ok = opt.ok(); if(!ok) return 1; + std::ofstream ex_time; + std::cout << getFileName(in_output) << std::endl; + ex_time.open("./output/" + getFileName(in_output) + "/" +"ex_time.txt", std::ios_base::app); + PointCloud points; ok = Loader::Load(in_input, points, in_v); if(!ok) return 1; @@ -57,6 +69,7 @@ int main(int argc, char **argv) << " (" << comp_data[i].size() << " pts)"; } } + clock_t start = clock(); // Persistence range ------------------------------------------------------- if(!in_ranges.empty()) @@ -184,6 +197,9 @@ int main(int argc, char **argv) } } } - + clock_t stop = clock(); + std::cout<<"END" << (double)(stop - start)/(CLOCKS_PER_SEC/1000)< +#include #include #include #include @@ -64,9 +65,17 @@ int main(int argc, char** argv) { tams::SubwindowRGSegmentation segmentation; segmentation.setparameters(parameters); segmentation.setInput(cloud); + + clock_t start = clock(); segmentation.preprocessing(); std::vector> indices = segmentation.applySegmentation(); + clock_t stop = clock(); + std::ofstream ex_time; + std::cout << pathToPCD.path().string() << std::endl; writeClustersInDataFolder(pathToPCD.path().string(), cloud, indices); + ex_time.open ("./output/" + getFileName(pathToPCD.path().string()) + "/" +"ex_time.txt"); + ex_time << "Elapsed(ms)=" << (double)(stop - start)/(CLOCKS_PER_SEC/1000) << std::endl; + ex_time.close(); } return 0; } \ No newline at end of file diff --git a/TAMS/scripts/build_colored_cloud.py b/TAMS/scripts/build_colored_cloud.py index 5390619e..c5a1c0e5 100644 --- a/TAMS/scripts/build_colored_cloud.py +++ b/TAMS/scripts/build_colored_cloud.py @@ -7,6 +7,8 @@ def create_colored_cloud(): rootdir = "./input" for file in os.listdir(rootdir): + if "ex_time" in file: + continue file_path = os.path.join(rootdir, file) npy_path = os.path.join("./output", file[:-4], file[:-4] + ".npy") labels = np.load(npy_path) diff --git a/TAMS/scripts/save_as_npy.py b/TAMS/scripts/save_as_npy.py index e1297682..ce2210dc 100644 --- a/TAMS/scripts/save_as_npy.py +++ b/TAMS/scripts/save_as_npy.py @@ -1,4 +1,5 @@ import os +from traceback import print_tb import numpy as np @@ -7,6 +8,9 @@ def convert_txt_files_to_npy_format(): for subdir, _, files in os.walk(rootdir): for file in files: + print(file) + if "ex_time" in file: + continue file_path = os.path.join(subdir, file) labels_array = np.loadtxt(file_path).astype(int) diff --git a/peac/cpp/plane_fitter_pcd.cpp b/peac/cpp/plane_fitter_pcd.cpp index 5abfbcda..92f83e74 100644 --- a/peac/cpp/plane_fitter_pcd.cpp +++ b/peac/cpp/plane_fitter_pcd.cpp @@ -194,6 +194,12 @@ void processOneFrame(pcl::PointCloud& cloud, const std::string& o double process_ms=timer.toc(); std::cout<