Wrap DSFMap so SFM can use them
							parent
							
								
									915702116f
								
							
						
					
					
						commit
						e43f78bfe8
					
				|  | @ -120,4 +120,12 @@ class IndexPair : public std::pair<size_t,size_t> { | |||
|   inline size_t i() const { return first; }; | ||||
|   inline size_t j() const { return second; }; | ||||
| }; | ||||
| 
 | ||||
| typedef std::vector<IndexPair> IndexPairVector; | ||||
| typedef std::set<IndexPair> IndexPairSet; | ||||
| 
 | ||||
| inline IndexPairVector IndexPairSetAsArray(IndexPairSet& set) { return IndexPairVector(set.begin(), set.end()); } | ||||
| 
 | ||||
| typedef std::map<IndexPair, IndexPairSet> IndexPairSetMap; | ||||
| typedef DSFMap<IndexPair> DSFMapIndexPair; | ||||
| }  // namespace gtsam
 | ||||
|  |  | |||
|  | @ -259,11 +259,59 @@ class IndexPair { | |||
|   size_t j() const; | ||||
| }; | ||||
| 
 | ||||
| template<KEY = {gtsam::IndexPair}> | ||||
| class DSFMap { | ||||
|   DSFMap(); | ||||
|   KEY find(const KEY& key) const; | ||||
|   void merge(const KEY& x, const KEY& y); | ||||
| // template<KEY = {gtsam::IndexPair}> | ||||
| // class DSFMap { | ||||
| //   DSFMap(); | ||||
| //   KEY find(const KEY& key) const; | ||||
| //   void merge(const KEY& x, const KEY& y); | ||||
| //   std::map<KEY, Set> sets(); | ||||
| // }; | ||||
| 
 | ||||
| class IndexPairSet { | ||||
|   IndexPairSet(); | ||||
|   // common STL methods | ||||
|   size_t size() const; | ||||
|   bool empty() const; | ||||
|   void clear(); | ||||
| 
 | ||||
|   // structure specific methods | ||||
|   void insert(gtsam::IndexPair key); | ||||
|   bool erase(gtsam::IndexPair key); // returns true if value was removed | ||||
|   bool count(gtsam::IndexPair key) const; // returns true if value exists | ||||
| }; | ||||
| 
 | ||||
| class IndexPairVector { | ||||
|   IndexPairVector(); | ||||
|   IndexPairVector(const gtsam::IndexPairVector& other); | ||||
| 
 | ||||
|   // common STL methods | ||||
|   size_t size() const; | ||||
|   bool empty() const; | ||||
|   void clear(); | ||||
| 
 | ||||
|   // structure specific methods | ||||
|   gtsam::IndexPair at(size_t i) const; | ||||
|   void push_back(gtsam::IndexPair key) const; | ||||
| }; | ||||
| 
 | ||||
| gtsam::IndexPairVector IndexPairSetAsArray(gtsam::IndexPairSet& set); | ||||
| 
 | ||||
| class IndexPairSetMap { | ||||
|   IndexPairSetMap(); | ||||
|   // common STL methods | ||||
|   size_t size() const; | ||||
|   bool empty() const; | ||||
|   void clear(); | ||||
| 
 | ||||
|   // structure specific methods | ||||
|   gtsam::IndexPairSet at(gtsam::IndexPair& key); | ||||
| }; | ||||
| 
 | ||||
| class DSFMapIndexPair { | ||||
|   DSFMapIndexPair(); | ||||
|   gtsam::IndexPair find(const gtsam::IndexPair& key) const; | ||||
|   void merge(const gtsam::IndexPair& x, const gtsam::IndexPair& y); | ||||
|   gtsam::IndexPairSetMap sets(); | ||||
| }; | ||||
| 
 | ||||
| #include <gtsam/base/Matrix.h> | ||||
|  |  | |||
|  | @ -30,6 +30,8 @@ set(ignore | |||
|     gtsam::ISAM2ThresholdMapValue | ||||
|     gtsam::FactorIndices | ||||
|     gtsam::FactorIndexSet | ||||
|     gtsam::IndexPairSetMap | ||||
|     gtsam::IndexPairVector | ||||
|     gtsam::BetweenFactorPose2s | ||||
|     gtsam::BetweenFactorPose3s | ||||
|     gtsam::Point2Vector | ||||
|  |  | |||
|  | @ -9,3 +9,4 @@ PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam:: | |||
| PYBIND11_MAKE_OPAQUE(std::vector<gtsam::Pose3>); | ||||
| PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > >); | ||||
| PYBIND11_MAKE_OPAQUE(std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > >); | ||||
| PYBIND11_MAKE_OPAQUE(std::vector<gtsam::IndexPair>); | ||||
|  |  | |||
|  | @ -9,3 +9,5 @@ py::bind_vector<std::vector<gtsam::Point2, Eigen::aligned_allocator<gtsam::Point | |||
| py::bind_vector<std::vector<gtsam::Pose3> >(m_, "Pose3Vector"); | ||||
| py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose3> > > >(m_, "BetweenFactorPose3s"); | ||||
| py::bind_vector<std::vector<boost::shared_ptr<gtsam::BetweenFactor<gtsam::Pose2> > > >(m_, "BetweenFactorPose2s"); | ||||
| py::bind_map<gtsam::IndexPairSetMap>(m_, "IndexPairSetMap"); | ||||
| py::bind_vector<gtsam::IndexPairVector>(m_, "IndexPairVector"); | ||||
		Loading…
	
		Reference in New Issue