diff --git a/.clang-format b/.clang-format index df7b1ca..6761564 100644 --- a/.clang-format +++ b/.clang-format @@ -1,7 +1,8 @@ --- -Language: Cpp +Language: Cpp ColumnLimit: 100 DerivePointerAlignment: false PointerAlignment: Left SortIncludes: false +InsertNewlineAtEOF: true ... diff --git a/examples/teaser_cpp_fpfh/quatro_cpp_fpfh.cc b/examples/teaser_cpp_fpfh/quatro_cpp_fpfh.cc index d802e56..5130107 100644 --- a/examples/teaser_cpp_fpfh/quatro_cpp_fpfh.cc +++ b/examples/teaser_cpp_fpfh/quatro_cpp_fpfh.cc @@ -16,8 +16,8 @@ inline double getAngularError(Eigen::Matrix3d R_exp, Eigen::Matrix3d R_est) { return std::abs(std::acos(fmin(fmax(((R_exp.transpose() * R_est).trace() - 1) / 2, -1.0), 1.0))); } -inline void calcErrors(const Eigen::Matrix4d& T, const Eigen::Matrix3d est_rot, const Eigen::Vector3d est_ts, - double &rot_error, double& ts_error) { +inline void calcErrors(const Eigen::Matrix4d& T, const Eigen::Matrix3d est_rot, + const Eigen::Vector3d est_ts, double& rot_error, double& ts_error) { rot_error = getAngularError(T.topLeftCorner(3, 3), est_rot); ts_error = (T.topRightCorner(3, 1) - est_ts).norm(); } @@ -32,11 +32,11 @@ inline void getParams(const double noise_bound, const std::string reg_type, if (reg_type == "Quatro") { params.rotation_estimation_algorithm = teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::QUATRO; - params.inlier_selection_mode == teaser::RobustRegistrationSolver::INLIER_SELECTION_MODE::PMC_HEU; - } else if (reg_type == "TEASER") { + params.inlier_selection_mode = teaser::RobustRegistrationSolver::INLIER_SELECTION_MODE::PMC_HEU; + } else if (reg_type == "TEASER") { params.rotation_estimation_algorithm = teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::GNC_TLS; - params.inlier_selection_mode == teaser::RobustRegistrationSolver::INLIER_SELECTION_MODE::PMC_EXACT; + params.inlier_selection_mode = teaser::RobustRegistrationSolver::INLIER_SELECTION_MODE::PMC_EXACT; } else { throw std::invalid_argument("Not implemented!"); } diff --git a/examples/teaser_cpp_ply/teaser_cpp_ply.cc b/examples/teaser_cpp_ply/teaser_cpp_ply.cc index a32d1c5..d4aa804 100644 --- a/examples/teaser_cpp_ply/teaser_cpp_ply.cc +++ b/examples/teaser_cpp_ply/teaser_cpp_ply.cc @@ -117,4 +117,4 @@ int main() { << std::chrono::duration_cast(end - begin).count() / 1000000.0 << std::endl; -} \ No newline at end of file +} diff --git a/examples/teaser_python_3dsmooth/teaser_python_3dsmooth.py b/examples/teaser_python_3dsmooth/teaser_python_3dsmooth.py index 406d956..7390989 100644 --- a/examples/teaser_python_3dsmooth/teaser_python_3dsmooth.py +++ b/examples/teaser_python_3dsmooth/teaser_python_3dsmooth.py @@ -109,7 +109,7 @@ def visualize_correspondences( frag2_temp.translate(translate) # estimate normals - vis_list = [target, source, frag1_temp, frag2_temp]; + vis_list = [target, source, frag1_temp, frag2_temp] for ii in vis_list: ii.estimate_normals() vis_list.extend([*inlier_line_mesh_geoms, *outlier_line_mesh_geoms]) diff --git a/python/teaserpp_python/teaserpp_python.cc b/python/teaserpp_python/teaserpp_python.cc index c1885b1..ac7d3c6 100644 --- a/python/teaserpp_python/teaserpp_python.cc +++ b/python/teaserpp_python/teaserpp_python.cc @@ -80,7 +80,8 @@ PYBIND11_MODULE(teaserpp_python, m) { py::enum_( solver, "ROTATION_ESTIMATION_ALGORITHM") .value("GNC_TLS", teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::GNC_TLS) - .value("FGR", teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::FGR); + .value("FGR", teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::FGR) + .value("QUATRO", teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::QUATRO); // Python bound for teaser::RobustRegistrationSolver::INLIER_GRAPH_FORMULATION py::enum_(solver, @@ -125,11 +126,19 @@ PYBIND11_MODULE(teaserpp_python, m) { .def("__repr__", [](const teaser::RobustRegistrationSolver::Params& a) { std::ostringstream print_string; - std::string rot_alg = - a.rotation_estimation_algorithm == - teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::FGR - ? "FGR" - : "GNC-TLS"; + std::string rot_alg; + if (a.rotation_estimation_algorithm == + teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::FGR) { + rot_alg = "FGR"; + } + if (a.rotation_estimation_algorithm == + teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::GNC_TLS) { + rot_alg = "GNC_TLS"; + } + if (a.rotation_estimation_algorithm == + teaser::RobustRegistrationSolver::ROTATION_ESTIMATION_ALGORITHM::QUATRO) { + rot_alg = "QUATRO"; + } std::string inlier_selection_alg; if (a.inlier_selection_mode == @@ -205,4 +214,4 @@ PYBIND11_MODULE(teaserpp_python, m) { .def_readwrite("gamma_tau", &teaser::DRSCertifier::Params::gamma_tau) .def_readwrite("eig_decomposition_solver", &teaser::DRSCertifier::Params::eig_decomposition_solver); -} \ No newline at end of file +} diff --git a/teaser/include/teaser/certification.h b/teaser/include/teaser/certification.h index 227d1a2..f17fee1 100644 --- a/teaser/include/teaser/certification.h +++ b/teaser/include/teaser/certification.h @@ -52,7 +52,6 @@ class AbstractRotationCertifier { */ class DRSCertifier : public AbstractRotationCertifier { public: - /** * Solver for eigendecomposition solver / spectral decomposition. * @@ -60,7 +59,7 @@ class DRSCertifier : public AbstractRotationCertifier { * For extremely large matrices, it may make sense to use Spectra instead. */ enum class EIG_SOLVER_TYPE { - EIGEN = 0, ///< Use solvers in the Eigen library + EIGEN = 0, ///< Use solvers in the Eigen library SPECTRA = 1, ///< Use solvers in the Spectra library }; @@ -237,4 +236,4 @@ class DRSCertifier : public AbstractRotationCertifier { Params params_; }; -} // namespace teaser \ No newline at end of file +} // namespace teaser diff --git a/teaser/include/teaser/fpfh.h b/teaser/include/teaser/fpfh.h index 6d7b9eb..720d8d2 100644 --- a/teaser/include/teaser/fpfh.h +++ b/teaser/include/teaser/fpfh.h @@ -11,6 +11,7 @@ #include #include #include +#include #include "teaser/geometry.h" @@ -21,10 +22,11 @@ using FPFHCloudPtr = pcl::PointCloud::Ptr; class FPFHEstimation { public: - FPFHEstimation() - : fpfh_estimation_( - new pcl::FPFHEstimationOMP){}; - + FPFHEstimation() { + fpfh_estimation_.reset( + new pcl::FPFHEstimationOMP()); + normals_.reset(new pcl::PointCloud()); + } /** * Compute FPFH features. * @@ -50,6 +52,8 @@ class FPFHEstimation { // pcl::FPFHEstimation::Ptr fpfh_estimation_; pcl::FPFHEstimationOMP::Ptr fpfh_estimation_; + pcl::PointCloud::Ptr normals_; + /** * Wrapper function for the corresponding PCL function. * @param output_cloud @@ -78,6 +82,12 @@ class FPFHEstimation { * Wrapper function for the corresponding PCL function. */ void setRadiusSearch(double); + + /** + * Return the normal vectors of the input cloud that are used in the calculation of FPFH + * @return + */ + pcl::PointCloud getNormals(); }; } // namespace teaser diff --git a/teaser/include/teaser/geometry.h b/teaser/include/teaser/geometry.h index 42ed50f..5474273 100644 --- a/teaser/include/teaser/geometry.h +++ b/teaser/include/teaser/geometry.h @@ -69,5 +69,4 @@ class PointCloud { std::vector points_; }; - } // namespace teaser diff --git a/teaser/include/teaser/graph.h b/teaser/include/teaser/graph.h index 4ac849f..f6e28cd 100644 --- a/teaser/include/teaser/graph.h +++ b/teaser/include/teaser/graph.h @@ -128,26 +128,26 @@ class Graph { * Get the number of vertices * @return total number of vertices */ - [[nodiscard]] int numVertices() const { return adj_list_.size(); } + int numVertices() const { return adj_list_.size(); } /** * Get the number of edges * @return total number of edges */ - [[nodiscard]] int numEdges() const { return num_edges_; } + int numEdges() const { return num_edges_; } /** * Get edges originated from a specific vertex * @param [in] id * @return an unordered set of edges */ - [[nodiscard]] const std::vector& getEdges(int id) const { return adj_list_[id]; } + const std::vector& getEdges(int id) const { return adj_list_[id]; } /** * Get all vertices * @return a vector of all vertices */ - [[nodiscard]] std::vector getVertices() const { + std::vector getVertices() const { std::vector v; for (int i = 0; i < adj_list_.size(); ++i) { v.push_back(i); @@ -155,7 +155,7 @@ class Graph { return v; } - [[nodiscard]] Eigen::MatrixXi getAdjMatrix() const { + Eigen::MatrixXi getAdjMatrix() const { const int num_v = numVertices(); Eigen::MatrixXi adj_matrix(num_v, num_v); for (size_t i = 0; i < num_v; ++i) { @@ -171,7 +171,7 @@ class Graph { return adj_matrix; } - [[nodiscard]] std::vector> getAdjList() const { return adj_list_; } + std::vector> getAdjList() const { return adj_list_; } /** * Preallocate spaces for vertices @@ -258,7 +258,7 @@ class MaxCliqueSolver { /** * Number of threads to use for the solver */ - int num_threads = 1; + int num_threads = 1; }; MaxCliqueSolver() = default; diff --git a/teaser/include/teaser/linalg.h b/teaser/include/teaser/linalg.h index c920ecf..9053076 100644 --- a/teaser/include/teaser/linalg.h +++ b/teaser/include/teaser/linalg.h @@ -98,4 +98,4 @@ void getNearestPSD(const Eigen::Matrix& A, *nearestPSD = Ve * De_positive * Ve.transpose(); } -} // namespace teaser \ No newline at end of file +} // namespace teaser diff --git a/teaser/include/teaser/macros.h b/teaser/include/teaser/macros.h index b6be4c9..383b6a6 100644 --- a/teaser/include/teaser/macros.h +++ b/teaser/include/teaser/macros.h @@ -65,5 +65,5 @@ auto t_end_##s = clock_##s.now(); \ std::chrono::duration diff_dur_##s = t_end_##s - t_start_##s; \ double diff_##s = diff_dur_##s.count(); -#define TEASER_DEBUG_GET_TIMING(s)(double)(diff_##s / 1000.0) -#endif \ No newline at end of file +#define TEASER_DEBUG_GET_TIMING(s) (double)(diff_##s / 1000.0) +#endif diff --git a/teaser/include/teaser/matcher.h b/teaser/include/teaser/matcher.h index 1b89d8f..e5e0fcb 100644 --- a/teaser/include/teaser/matcher.h +++ b/teaser/include/teaser/matcher.h @@ -36,11 +36,11 @@ class Matcher { * @param use_tuple_test * @return */ - std::vector> - calculateCorrespondences(teaser::PointCloud& source_points, teaser::PointCloud& target_points, - teaser::FPFHCloud& source_features, teaser::FPFHCloud& target_features, - bool use_absolute_scale = true, bool use_crosscheck = true, - bool use_tuple_test = true, float tuple_scale = 0); + std::vector> calculateCorrespondences( + const teaser::PointCloud& source_points, const teaser::PointCloud& target_points, + const teaser::FPFHCloud& source_features, const teaser::FPFHCloud& target_features, + bool use_absolute_scale = true, bool use_crosscheck = true, bool use_tuple_test = true, + float tuple_scale = 0); private: template void buildKDTree(const std::vector& data, KDTree* tree); @@ -56,7 +56,7 @@ class Matcher { std::vector> corres_; std::vector pointcloud_; std::vector features_; - std::vector > means_; // for normalization + std::vector> means_; // for normalization float global_scale_; }; diff --git a/teaser/src/certification.cc b/teaser/src/certification.cc index 08b0a3f..cb4cc58 100644 --- a/teaser/src/certification.cc +++ b/teaser/src/certification.cc @@ -97,7 +97,7 @@ teaser::DRSCertifier::certify(const Eigen::Matrix3d& R_solution, // this initial guess lives in the affine subspace // use 2 separate steps to limit slow evaluation on only the few non-zeros in the sparse matrix -#if EIGEN_VERSION_AT_LEAST(3,3,0) +#if EIGEN_VERSION_AT_LEAST(3, 3, 0) Eigen::SparseMatrix M_init = Q_bar - mu * J_bar - lambda_bar_init; #else // fix for this bug in Eigen 3.2: https://eigen.tuxfamily.org/bz/show_bug.cgi?id=632 @@ -135,7 +135,7 @@ teaser::DRSCertifier::certify(const Eigen::Matrix3d& R_solution, TEASER_DEBUG_INFO_MSG("PSD time: " << TEASER_DEBUG_GET_TIMING(PSD)); // projection to affine space -#if EIGEN_VERSION_AT_LEAST(3,3,0) +#if EIGEN_VERSION_AT_LEAST(3, 3, 0) temp_W = 2 * M_PSD - M - M_init; #else // fix for this bug in Eigen 3.2: https://eigen.tuxfamily.org/bz/show_bug.cgi?id=632 @@ -147,7 +147,7 @@ teaser::DRSCertifier::certify(const Eigen::Matrix3d& R_solution, getOptimalDualProjection(temp_W, theta_prepended, inverse_map, &W_dual); TEASER_DEBUG_STOP_TIMING(DualProjection); TEASER_DEBUG_INFO_MSG("Dual Projection time: " << TEASER_DEBUG_GET_TIMING(DualProjection)); -#if EIGEN_VERSION_AT_LEAST(3,3,0) +#if EIGEN_VERSION_AT_LEAST(3, 3, 0) M_affine = M_init + W_dual; #else // fix for this bug in Eigen 3.2: https://eigen.tuxfamily.org/bz/show_bug.cgi?id=632 @@ -604,7 +604,7 @@ void teaser::DRSCertifier::getLinearProjection( temp_column.emplace_back(var_i_idx, var_j_idx, entry_val); if (var_i_idx == var_j_idx) { diag_inserted = true; - diag_idx = temp_column.size()-1; + diag_idx = temp_column.size() - 1; } } } @@ -623,7 +623,7 @@ void teaser::DRSCertifier::getLinearProjection( temp_column.emplace_back(var_i_idx, var_j_idx, entry_val); if (var_i_idx == var_j_idx) { diag_inserted = true; - diag_idx = temp_column.size()-1; + diag_idx = temp_column.size() - 1; } } } diff --git a/teaser/src/fpfh.cc b/teaser/src/fpfh.cc index 27d6d10..59396d3 100644 --- a/teaser/src/fpfh.cc +++ b/teaser/src/fpfh.cc @@ -16,7 +16,6 @@ teaser::FPFHCloudPtr teaser::FPFHEstimation::computeFPFHFeatures( const teaser::PointCloud& input_cloud, double normal_search_radius, double fpfh_search_radius) { // Intermediate variables - pcl::PointCloud::Ptr normals(new pcl::PointCloud); teaser::FPFHCloudPtr descriptors(new pcl::PointCloud()); pcl::PointCloud::Ptr pcl_input_cloud(new pcl::PointCloud); for (auto& i : input_cloud) { @@ -25,16 +24,17 @@ teaser::FPFHCloudPtr teaser::FPFHEstimation::computeFPFHFeatures( } // Estimate normals - pcl::NormalEstimation normalEstimation; + normals_->clear(); + pcl::NormalEstimationOMP normalEstimation; normalEstimation.setInputCloud(pcl_input_cloud); normalEstimation.setRadiusSearch(normal_search_radius); pcl::search::KdTree::Ptr kdtree(new pcl::search::KdTree); normalEstimation.setSearchMethod(kdtree); - normalEstimation.compute(*normals); + normalEstimation.compute(*normals_); // Estimate FPFH setInputCloud(pcl_input_cloud); - setInputNormals(normals); + setInputNormals(normals_); setSearchMethod(kdtree); setRadiusSearch(fpfh_search_radius); compute(*descriptors); @@ -59,3 +59,5 @@ void teaser::FPFHEstimation::compute(pcl::PointCloud& outp fpfh_estimation_->compute(output_cloud); } void teaser::FPFHEstimation::setRadiusSearch(double r) { fpfh_estimation_->setRadiusSearch(r); } + +pcl::PointCloud teaser::FPFHEstimation::getNormals() { return *normals_; } diff --git a/teaser/src/graph.cc b/teaser/src/graph.cc index ca95862..e1c2ea7 100644 --- a/teaser/src/graph.cc +++ b/teaser/src/graph.cc @@ -74,7 +74,7 @@ vector teaser::MaxCliqueSolver::findMaxClique(teaser::Graph graph) { for (int i = 1; i < k_cores->size(); ++i) { // Note: k_core has size equals to num vertices + 1 if ((*k_cores)[i] >= max_core) { - C.push_back(i-1); + C.push_back(i - 1); } } return C; diff --git a/teaser/src/matcher.cc b/teaser/src/matcher.cc index b87d1df..0156697 100644 --- a/teaser/src/matcher.cc +++ b/teaser/src/matcher.cc @@ -6,7 +6,6 @@ * See LICENSE for the license information */ - #include #include #include @@ -20,9 +19,9 @@ namespace teaser { std::vector> Matcher::calculateCorrespondences( - teaser::PointCloud& source_points, teaser::PointCloud& target_points, - teaser::FPFHCloud& source_features, teaser::FPFHCloud& target_features, bool use_absolute_scale, - bool use_crosscheck, bool use_tuple_test, float tuple_scale) { + const teaser::PointCloud& source_points, const teaser::PointCloud& target_points, + const teaser::FPFHCloud& source_features, const teaser::FPFHCloud& target_features, + bool use_absolute_scale, bool use_crosscheck, bool use_tuple_test, float tuple_scale) { Feature cloud_features; pointcloud_.push_back(source_points); @@ -138,9 +137,8 @@ void Matcher::advancedMatching(bool use_crosscheck, bool use_tuple_test, float t KDTree feature_tree_j(flann::KDTreeSingleIndexParams(15)); buildKDTree(features_[fj], &feature_tree_j); - std::vector corres_K, corres_K2; + std::vector corres_K; std::vector dis; - std::vector ind; std::vector> corres; std::vector> corres_cross; diff --git a/teaser/src/registration.cc b/teaser/src/registration.cc index 4b1b8b9..c4e98f7 100644 --- a/teaser/src/registration.cc +++ b/teaser/src/registration.cc @@ -378,13 +378,11 @@ void teaser::QuatroSolver::solveForRotation( weights(j) = sqrt(noise_bound_sq * mu * (mu + 1) / residuals_sq(j)) - mu; assert(weights(j) >= 0 && weights(j) <= 1); } - } // Calculate cost double cost_diff = std::abs(cost_ - prev_cost); - // Increase mu mu = mu * params_.gnc_factor; prev_cost = cost_; diff --git a/test/teaser/feature-test.cc b/test/teaser/feature-test.cc index 91ea08d..15ec149 100644 --- a/test/teaser/feature-test.cc +++ b/test/teaser/feature-test.cc @@ -26,7 +26,7 @@ TEST(FPFHTest, CalculateFPFHFeaturesWithPCL) { // Read a PCD file from disk. pcl::PCLPointCloud2 cloud_blob; pcl::io::loadPCDFile("./data/bunny.pcd", cloud_blob); - pcl::fromPCLPointCloud2 (cloud_blob, *cloud); + pcl::fromPCLPointCloud2(cloud_blob, *cloud); // Estimate the normals. pcl::NormalEstimation normalEstimation; @@ -53,7 +53,7 @@ TEST(FPFHTest, CalculateFPFHFeaturesWithTeaserInterface) { pcl::PointCloud::Ptr pcl_cloud(new pcl::PointCloud); pcl::PCLPointCloud2 cloud_blob; pcl::io::loadPCDFile("./data/bunny.pcd", cloud_blob); - pcl::fromPCLPointCloud2 (cloud_blob, *pcl_cloud); + pcl::fromPCLPointCloud2(cloud_blob, *pcl_cloud); teaser::PointCloud input_cloud; for (auto& p : *pcl_cloud) { input_cloud.push_back({p.x, p.y, p.z}); diff --git a/test/teaser/graph-test.cc b/test/teaser/graph-test.cc index 4057e3f..cdcfd94 100644 --- a/test/teaser/graph-test.cc +++ b/test/teaser/graph-test.cc @@ -63,7 +63,7 @@ TEST(GraphTest, BasicFunctions) { teaser::Graph graph; graph.populateVertices(2); graph.addEdge(1, 0); - EXPECT_TRUE(graph.hasEdge(1,0)); + EXPECT_TRUE(graph.hasEdge(1, 0)); EXPECT_TRUE(graph.hasVertex(1)); EXPECT_TRUE(graph.hasVertex(0)); EXPECT_EQ(graph.numEdges(), 1); @@ -297,7 +297,7 @@ TEST(MaxCliqueSolverTest, FindMaxClique) { std::copy(clique.begin(), clique.end(), std::ostream_iterator(std::cout, " ")); std::cout << std::endl; std::set s(clique.begin(), clique.end()); - std::vector ref_clique{0,1,2,3,4}; + std::vector ref_clique{0, 1, 2, 3, 4}; for (const auto& i : ref_clique) { EXPECT_TRUE(s.find(i) != s.end()); } @@ -356,7 +356,6 @@ TEST(PMCTest, FindMaximumCliqueSingleThreaded) { EXPECT_EQ(C.size(), 5); } - TEST(PMCTest, FindMaximumCliqueMultiThreaded) { // A complete graph with max clique # = 5 auto in = generateMockInput(); diff --git a/test/teaser/matcher-test.cc b/test/teaser/matcher-test.cc index 2103a31..549db58 100644 --- a/test/teaser/matcher-test.cc +++ b/test/teaser/matcher-test.cc @@ -67,7 +67,7 @@ TEST(FPFHMatcherTest, MatchCase1) { ASSERT_EQ(tokens.size(), 2); ref_correspondences.emplace_back( // -1 because the ref correspondences use 1-index (MATLAB) - std::pair{std::stoi(tokens[0])-1, std::stoi(tokens[1])-1}); + std::pair{std::stoi(tokens[0]) - 1, std::stoi(tokens[1]) - 1}); } // compare calculated correspondences with reference correspondences diff --git a/test/teaser/rotation-solver-test.cc b/test/teaser/rotation-solver-test.cc index fd9f3b1..8434736 100644 --- a/test/teaser/rotation-solver-test.cc +++ b/test/teaser/rotation-solver-test.cc @@ -31,7 +31,7 @@ TEST(RotationSolverTest, FGRRotation) { Eigen::Matrix dst_points = src_points; // Set up FGR - teaser::FastGlobalRegistrationSolver::Params params{1000, 0.0337, 1.4, 1e-3}; + teaser::FastGlobalRegistrationSolver::Params params{1000, 0.0337, 1.4, 1e-3}; teaser::FastGlobalRegistrationSolver fgr_solver(params); Eigen::Matrix3d result; diff --git a/test/teaser/utils-test.cc b/test/teaser/utils-test.cc index 193ff90..32b74e7 100644 --- a/test/teaser/utils-test.cc +++ b/test/teaser/utils-test.cc @@ -115,8 +115,8 @@ TEST(UtilsTest, CalculatePointClusterDiameter) { { Eigen::Matrix test_mat(3,3); test_mat << -1, 0, 1, - -1, 0, 1, - -1, 0, 1; + -1, 0, 1, + -1, 0, 1; float d = teaser::utils::calculateDiameter(test_mat); EXPECT_NEAR(d, 3.4641, 0.0001); } @@ -128,4 +128,4 @@ TEST(UtilsTest, CalculatePointClusterDiameter) { float d = teaser::utils::calculateDiameter(test_mat); EXPECT_NEAR(d, 5.1962, 0.0001); } -} \ No newline at end of file +} diff --git a/test/test-tools/test_utils.h b/test/test-tools/test_utils.h index 878442a..e28e20f 100644 --- a/test/test-tools/test_utils.h +++ b/test/test-tools/test_utils.h @@ -132,4 +132,4 @@ inline std::vector readSubdirs(std::string path) { } } // namespace test -} // namespace teaser \ No newline at end of file +} // namespace teaser