From 5070828faf5dc09dff54dbf6dd49b7afc7339665 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Sol=C3=A0?= <jsola@iri.upc.edu> Date: Wed, 10 Aug 2022 21:19:28 +0200 Subject: [PATCH] Remove old duration info --- include/laser/utils/laser3d_tools.h | 16 ++-------------- 1 file changed, 2 insertions(+), 14 deletions(-) diff --git a/include/laser/utils/laser3d_tools.h b/include/laser/utils/laser3d_tools.h index 7992d951a..bb8d56fd1 100644 --- a/include/laser/utils/laser3d_tools.h +++ b/include/laser/utils/laser3d_tools.h @@ -64,11 +64,6 @@ inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud_ref, _registration_solver->setInputSource(cloud_ref); _registration_solver->setInputTarget(cloud_other); - // DURATION -------------------------------------------------------- - auto end_downsampling = std::chrono::high_resolution_clock::now(); - auto start_aligning = std::chrono::high_resolution_clock::now(); - // DURATION -------------------------------------------------------- - // Declare variables Eigen::Matrix4f transform_pcl; @@ -83,15 +78,8 @@ inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud_ref, _transform_final = Eigen::Isometry3d(transform_pcl.cast<double>()); // DURATION -------------------------------------------------------- - auto end = std::chrono::high_resolution_clock::now(); - - auto duration_downsampling = std::chrono::duration_cast<std::chrono::microseconds>(end_downsampling - start); - auto duration_align = std::chrono::duration_cast<std::chrono::microseconds>(end - start_aligning); - auto duration_total = std::chrono::duration_cast<std::chrono::microseconds>(end - start); - - WOLF_INFO("Laser3d_tools.h: Duration downsampling: ", 1e-3 * (duration_downsampling).count(), " ms"); - WOLF_INFO("Laser3d_tools.h: Duration aligning : ", 1e-3 * (duration_align).count(), " ms"); - WOLF_INFO("Laser3d_tools.h: Duration total : ", 1e-3 * (duration_total).count(), " ms"); + auto duration = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::high_resolution_clock::now() - start); + WOLF_INFO("Laser3d_tools.h: pairAlign: duration: ", 1e-3 * (duration).count(), " ms"); // DURATION -------------------------------------------------------- } -- GitLab