diff --git a/gtsam/base/kruskal-inl.h b/gtsam/base/kruskal-inl.h index 4b66a905f..d610541a0 100644 --- a/gtsam/base/kruskal-inl.h +++ b/gtsam/base/kruskal-inl.h @@ -12,7 +12,9 @@ /** * @file kruskal-inl.h * @date Dec 31, 2009 - * @author Frank Dellaert, Yong-Dian Jian + * @author Frank Dellaert + * @author Yong-Dian Jian + * @author Ankur Roy Chowdhury */ #pragma once @@ -20,37 +22,37 @@ #include #include #include -#include #include -#include +#include +#include #include namespace gtsam::utils { /*****************************************************************************/ -/* sort the container and return permutation index with default comparator */ -inline std::vector sortedIndices(const std::vector &src) { - const size_t n = src.size(); - std::vector> tmp; - tmp.reserve(n); - for (size_t i = 0; i < n; i++) tmp.emplace_back(i, src[i]); +/* Sort the 'weights' in increasing order and return the sorted order of its + * indices. */ +inline std::vector sortedIndices(const std::vector &weights) { + // Get the number of elements in the 'weights' vector. + const size_t n = weights.size(); - /* sort */ - std::stable_sort(tmp.begin(), tmp.end()); + // Create a vector of 'indices'. + std::vector indices(n); + std::iota(indices.begin(), indices.end(), 0); - /* copy back */ - std::vector idx; - idx.reserve(n); - for (size_t i = 0; i < n; i++) { - idx.push_back(tmp[i].first); - } - return idx; + // Sort the 'indices' based on the values in 'weights'. + std::stable_sort(indices.begin(), indices.end(), + [&weights](const size_t i0, const size_t i1) { + return weights[i0] < weights[i1]; + }); + + return indices; } /****************************************************************/ -template -std::vector kruskal(const Graph &fg, +template +std::vector kruskal(const FactorGraph &fg, const std::vector &weights) { if (fg.size() != weights.size()) { throw std::runtime_error( @@ -61,7 +63,7 @@ std::vector kruskal(const Graph &fg, // Create an index from variables to factor indices. const VariableIndex variableIndex(fg); - // Get indices in sort-order of the weights + // Get indices in sort-order of the weights. const std::vector sortedIndices = gtsam::utils::sortedIndices(weights); @@ -81,11 +83,20 @@ std::vector kruskal(const Graph &fg, // Ignore non-binary edges. if (factor->size() != 2) continue; - auto u = dsf.find(factor->front()), v = dsf.find(factor->back()); - auto loop = (u == v); + // Find the representatives of the sets for both the Keys in the binary + // factor. + const auto u = dsf.find(factor->front()), v = dsf.find(factor->back()); + + // Check if there is a potential loop. + const bool loop = (u == v); if (!loop) { + // Merge the sets. dsf.merge(u, v); + + // Add the current index to the tree. treeIndices.push_back(index); + + // Break if all the Keys have been added to the tree. if (++count == n - 1) break; } } diff --git a/gtsam/base/kruskal.h b/gtsam/base/kruskal.h index 4b7493685..058c22435 100644 --- a/gtsam/base/kruskal.h +++ b/gtsam/base/kruskal.h @@ -20,6 +20,7 @@ #pragma once #include +#include #include @@ -32,9 +33,9 @@ namespace gtsam::utils { * @note Only binary factors are considered while constructing the spanning tree * @note The indices of 'weights' should match the indices of the edges in the factor graph */ -template -std::vector kruskal(const FactorGraph &fg, +template +std::vector kruskal(const FactorGraph &fg, const std::vector &weights); } // namespace gtsam::utils -#include \ No newline at end of file +#include diff --git a/gtsam/linear/SubgraphBuilder.cpp b/gtsam/linear/SubgraphBuilder.cpp index bf9343c81..40121d7cc 100644 --- a/gtsam/linear/SubgraphBuilder.cpp +++ b/gtsam/linear/SubgraphBuilder.cpp @@ -359,7 +359,6 @@ Subgraph SubgraphBuilder::operator()(const GaussianFactorGraph &gfg) const { /****************************************************************/ SubgraphBuilder::Weights SubgraphBuilder::weights( const GaussianFactorGraph &gfg) const { - using Weights = std::vector; const size_t m = gfg.size(); Weights weight; diff --git a/gtsam/linear/SubgraphBuilder.h b/gtsam/linear/SubgraphBuilder.h index 60dfefe24..aafba9306 100644 --- a/gtsam/linear/SubgraphBuilder.h +++ b/gtsam/linear/SubgraphBuilder.h @@ -185,4 +185,4 @@ GaussianFactorGraph buildFactorSubgraph(const GaussianFactorGraph &gfg, std::pair splitFactorGraph( const GaussianFactorGraph &factorGraph, const Subgraph &subgraph); -} // namespace gtsam \ No newline at end of file +} // namespace gtsam diff --git a/gtsam/slam/lago.h b/gtsam/slam/lago.h index 0dfccdd58..5661a7cba 100644 --- a/gtsam/slam/lago.h +++ b/gtsam/slam/lago.h @@ -70,9 +70,9 @@ GTSAM_EXPORT GaussianFactorGraph buildLinearOrientationGraph( const std::vector& chordsIds, const NonlinearFactorGraph& g, const key2doubleMap& orientationsToRoot, const PredecessorMap& tree); -/** Given a "pose2" factor graph, find it's minimum spanning tree. - * Note: all 'Pose2' Between factors are given equal weightage. - * Note: assumes all the edges (factors) are Between factors +/** Given a "pose2" factor graph, find its minimum spanning tree. + * Note: All 'Pose2' Between factors are given equal weightage. + * Note: Assumes all the edges (factors) are Between factors. */ GTSAM_EXPORT PredecessorMap findMinimumSpanningTree( const NonlinearFactorGraph& pose2Graph); diff --git a/tests/testSubgraphSolver.cpp b/tests/testSubgraphSolver.cpp index 616c77062..69b5fe5f9 100644 --- a/tests/testSubgraphSolver.cpp +++ b/tests/testSubgraphSolver.cpp @@ -129,7 +129,6 @@ TEST( SubgraphSolver, constructor3 ) DOUBLES_EQUAL(0.0, error(Ab, optimized), 1e-5); } - /* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); } /* ************************************************************************* */