From d1a62b0cc17057fcf696a065412ab3214005fcb4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 27 Oct 2013 02:50:47 +0000 Subject: [PATCH] Killed other variants --- gtsam_unstable/base/DSFMap.h | 219 +++--------------- gtsam_unstable/base/tests/testDSFMap.cpp | 12 +- gtsam_unstable/base/tests/timeDSFvariants.cpp | 12 +- 3 files changed, 37 insertions(+), 206 deletions(-) diff --git a/gtsam_unstable/base/DSFMap.h b/gtsam_unstable/base/DSFMap.h index bfc6d4b84..dc6b99dbd 100644 --- a/gtsam_unstable/base/DSFMap.h +++ b/gtsam_unstable/base/DSFMap.h @@ -18,154 +18,19 @@ #pragma once -#include #include #include -#include namespace gtsam { /** * Disjoint set forest using an STL map data structure underneath - * Uses rank compression but not union by rank :-( + * Uses rank compression and union by rank, iterator version * @addtogroup base */ template class DSFMap { -protected: - - /// We store the forest in an STL map - typedef std::map Map; - typedef std::set Set; - typedef std::pair key_pair; - mutable Map parent_; - -public: - /// constructor - DSFMap() { - } - - /// find the label of the set in which {key} lives - KEY find(const KEY& key) const { - typename Map::const_iterator it = parent_.find(key); - // if key does not exist, create and return itself - if (it == parent_.end()) { - parent_[key] = key; - return key; - } else { - // follow parent pointers until we reach set representative - KEY parent = it->second; - if (parent != key) - parent = find(parent); // not yet, recurse! - parent_[key] = parent; // path compression - return parent; - } - } - - /// Merge two sets - void merge(const KEY& i1, const KEY& i2) { - parent_[find(i2)] = find(i1); - } - - /// return all sets, i.e. a partition of all elements - std::map sets() const { - std::map sets; - BOOST_FOREACH(const key_pair& pair, parent_) - sets[find(pair.second)].insert(pair.first); - return sets; - } - -}; - -/** - * Disjoint set forest using an STL map data structure underneath - * Uses rank compression but not union by rank :-( - * @addtogroup base - */ -template -class DSFMapIt { - -protected: - - /// We store the forest in an STL map, but parents are done with pointers - struct Entry { - typedef std::map Map; - typename Map::iterator parent_; - size_t rank_; - Entry() : - rank_(0) { - } - void makeRoot(const typename Map::iterator& it) { - parent_ = it; - } - }; - mutable typename Entry::Map entries_; - - /// find the initial Entry - typename Entry::Map::iterator find__(const KEY& key) const { - typename Entry::Map::iterator it = entries_.find(key); - // if key does not exist, create and return itself - if (it == entries_.end()) { - it = entries_.insert(it, std::make_pair(key, Entry())); - it->second.makeRoot(it); - } - return it; - } - - /// find the root Entry - typename Entry::Map::iterator find_(const KEY& key) const { - typename Entry::Map::iterator initial = find__(key); - // follow parent pointers until we reach set representative - typename Entry::Map::iterator parent = initial->second.parent_; - while (parent->second.parent_ != parent) - parent = parent->second.parent_; // not yet, recurse! - //initial.parent_ = parent; // path compression - return parent; - } - -public: - /// constructor - DSFMapIt() { - } - - /// find the representative KEY for the set in which key lives - KEY find(const KEY& key) const { - typename Entry::Map::iterator root = find_(key); - return root->first; - } - - /// Merge two sets - void merge(const KEY& x, const KEY& y) { - - // straight from http://en.wikipedia.org/wiki/Disjoint-set_data_structure - typename Entry::Map::iterator xRoot = find_(x); - typename Entry::Map::iterator yRoot = find_(y); - if (xRoot == yRoot) - return; - - // Merge sets - size_t xRootRank = xRoot->second.rank_, yRootRank = yRoot->second.rank_; - if (xRootRank < yRootRank) - xRoot->second.parent_ = yRoot; - else if (xRootRank > yRootRank) - yRoot->second.parent_ = xRoot; - else { - yRoot->second.parent_ = xRoot; - xRoot->second.rank_ = xRootRank + 1; - } - } - -}; - -/** - * Disjoint set forest using an STL map data structure underneath - * Uses rank compression but not union by rank :-( - * @addtogroup base - */ -template -class DSFMap2 { - protected: /// We store the forest in an STL map, but parents are done with pointers @@ -180,37 +45,46 @@ protected: parent_ = this; } }; + typedef std::map Map; mutable Map entries_; - /// find the initial Entry - Entry& find__(const KEY& key) const { + /// Given key, find iterator to initial entry + typename Map::iterator find__(const KEY& key) const { typename Map::iterator it = entries_.find(key); // if key does not exist, create and return itself if (it == entries_.end()) { it = entries_.insert(it, std::make_pair(key, Entry(key))); it->second.makeRoot(); } - return it->second; + return it; } - /// find the root Entry - Entry* find_(const KEY& key) const { - Entry& initial = find__(key); + /// Given iterator to initial entry, find the root Entry + Entry* find_(const typename Map::iterator& it) const { // follow parent pointers until we reach set representative - Entry* parent = initial.parent_; + Entry* parent = it->second.parent_; while (parent->parent_ != parent) parent = parent->parent_; // not yet, recurse! - initial.parent_ = parent; // path compression + it->second.parent_ = parent; // path compression return parent; } -public: - /// constructor - DSFMap2() { + /// Given key, find the root Entry + Entry* find_(const KEY& key) const { + typename Map::iterator it = find__(key); + return find_(it); } - /// find the representative KEY for the set in which key lives +public: + + typedef std::set Set; + + /// constructor + DSFMap() { + } + + /// Given key, find the representative key for the set in which it lives KEY find(const KEY& key) const { Entry* root = find_(key); return root->key_; @@ -236,48 +110,15 @@ public: } } -}; - -/** - * DSFMap version that uses union by rank :-) - * @addtogroup base - */ -template -class DSFMap3: public DSFMap { - - /// We store rank in an STL map as well - typedef std::map Ranks; - mutable Ranks rank_; - - size_t rank(const KEY& i) const { - typename Ranks::const_iterator it = rank_.find(i); - return it == rank_.end() ? 0 : it->second; - } - -public: - /// constructor - DSFMap3() { - } - - /// Merge two sets - void merge(const KEY& x, const KEY& y) { - - // straight from http://en.wikipedia.org/wiki/Disjoint-set_data_structure - KEY xRoot = this->find(x); - KEY yRoot = this->find(y); - if (xRoot == yRoot) - return; - - // Merge sets - size_t xRootRank = rank(xRoot), yRootRank = rank(yRoot); - if (xRootRank < yRootRank) - this->parent_[xRoot] = yRoot; - else if (xRootRank > yRootRank) - this->parent_[yRoot] = xRoot; - else { - this->parent_[yRoot] = xRoot; - this->rank_[xRoot] = xRootRank + 1; + /// return all sets, i.e. a partition of all elements + std::map sets() const { + std::map sets; + typename Map::iterator it = entries_.begin(); + for(;it!=entries_.end();it++) { + Entry* root = find_(it); + sets[root->key_].insert(it->first); } + return sets; } }; diff --git a/gtsam_unstable/base/tests/testDSFMap.cpp b/gtsam_unstable/base/tests/testDSFMap.cpp index 720519f13..69723d99b 100644 --- a/gtsam_unstable/base/tests/testDSFMap.cpp +++ b/gtsam_unstable/base/tests/testDSFMap.cpp @@ -32,7 +32,7 @@ using namespace gtsam; /* ************************************************************************* */ TEST(DSFMap, find) { - DSFMapIt dsf; + DSFMap dsf; EXPECT(dsf.find(0)==0); EXPECT(dsf.find(2)==2); EXPECT(dsf.find(0)==0); @@ -42,21 +42,21 @@ TEST(DSFMap, find) { /* ************************************************************************* */ TEST(DSFMap, merge) { - DSFMapIt dsf; + DSFMap dsf; dsf.merge(0,2); EXPECT(dsf.find(0) == dsf.find(2)); } /* ************************************************************************* */ TEST(DSFMap, merge2) { - DSFMapIt dsf; + DSFMap dsf; dsf.merge(2,0); EXPECT(dsf.find(0) == dsf.find(2)); } /* ************************************************************************* */ TEST(DSFMap, merge3) { - DSFMapIt dsf; + DSFMap dsf; dsf.merge(0,1); dsf.merge(1,2); EXPECT(dsf.find(0) == dsf.find(2)); @@ -71,7 +71,7 @@ TEST(DSFMap, mergePairwiseMatches) { matches += Match(1,2), Match(2,3), Match(4,5), Match(4,6); // Merge matches - DSFMapIt dsf; + DSFMap dsf; BOOST_FOREACH(const Match& m, matches) dsf.merge(m.first,m.second); @@ -101,7 +101,7 @@ TEST(DSFMap, mergePairwiseMatches2) { matches += Match(m11,m22), Match(m12,m23), Match(m14,m25), Match(m14,m26); // Merge matches - DSFMapIt dsf; + DSFMap dsf; BOOST_FOREACH(const Match& m, matches) dsf.merge(m.first,m.second); diff --git a/gtsam_unstable/base/tests/timeDSFvariants.cpp b/gtsam_unstable/base/tests/timeDSFvariants.cpp index 938d8dde7..134c318cb 100644 --- a/gtsam_unstable/base/tests/timeDSFvariants.cpp +++ b/gtsam_unstable/base/tests/timeDSFvariants.cpp @@ -82,17 +82,7 @@ int main(int argc, char* argv[]) { { // DSFMap version timer tim; - DSFMapIt dsf; - BOOST_FOREACH(const Match& m, matches) - dsf.merge(m.first, m.second); - os << tim.elapsed() << ","; - cout << format("DSFMap: %1% s") % tim.elapsed() << endl; - } - - { - // DSFMap2 version - timer tim; - DSFMap2 dsf; + DSFMap dsf; BOOST_FOREACH(const Match& m, matches) dsf.merge(m.first, m.second); os << tim.elapsed() << endl;