diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 649d80ae3..df486e19e 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -3114,16 +3114,16 @@ class KeyPairDoubleMap { size_t size() const; bool empty() const; void clear(); - size_t at(pair) const; + size_t at(const pair& keypair) const; }; class MFAS { - MFAS(const KeyVector*& nodes, + MFAS(const gtsam::KeyVector* nodes, const gtsam::BinaryMeasurementsUnit3& relativeTranslations, const gtsam::Unit3& projectionDirection); - KeyPairDoubleMap computeOutlierWeights() const; - KeyVector computeOrdering() const; + gtsam::KeyPairDoubleMap computeOutlierWeights() const; + gtsam::KeyVector computeOrdering() const; }; #include diff --git a/gtsam/sfm/MFAS.cpp b/gtsam/sfm/MFAS.cpp index 6dccc2dee..0a407785b 100644 --- a/gtsam/sfm/MFAS.cpp +++ b/gtsam/sfm/MFAS.cpp @@ -7,6 +7,8 @@ #include +#include + #include #include #include @@ -111,7 +113,7 @@ void removeNodeFromGraph(const Key node, graph.erase(node); } -MFAS::MFAS(const std::shared_ptr>& nodes, +MFAS::MFAS(const boost::shared_ptr> nodes, const TranslationEdges& relativeTranslations, const Unit3& projectionDirection) : nodes_(nodes) { diff --git a/gtsam/sfm/MFAS.h b/gtsam/sfm/MFAS.h index 67a7df219..ca85d3248 100644 --- a/gtsam/sfm/MFAS.h +++ b/gtsam/sfm/MFAS.h @@ -22,6 +22,8 @@ #include #include +#include + #include #include #include @@ -57,7 +59,7 @@ class MFAS { private: // pointer to nodes in the graph - const std::shared_ptr> nodes_; + const boost::shared_ptr> nodes_; // edges with a direction such that all weights are positive // i.e, edges that originally had negative weights are flipped @@ -74,7 +76,7 @@ class MFAS { * @param nodes: Nodes in the graph * @param edgeWeights: weights of edges in the graph */ - MFAS(const std::shared_ptr> &nodes, + MFAS(const boost::shared_ptr> nodes, const std::map &edgeWeights) : nodes_(nodes), edgeWeights_(edgeWeights) {} @@ -88,7 +90,7 @@ class MFAS { * @param relativeTranslations translation directions between the cameras * @param projectionDirection direction in which edges are to be projected */ - MFAS(const std::shared_ptr> &nodes, + MFAS(const boost::shared_ptr> nodes, const TranslationEdges &relativeTranslations, const Unit3 &projectionDirection); diff --git a/gtsam/sfm/tests/testMFAS.cpp b/gtsam/sfm/tests/testMFAS.cpp index 58ea4cc84..53526cce1 100644 --- a/gtsam/sfm/tests/testMFAS.cpp +++ b/gtsam/sfm/tests/testMFAS.cpp @@ -6,9 +6,13 @@ */ #include -#include + +#include +#include #include +#include + using namespace std; using namespace gtsam; @@ -46,7 +50,7 @@ map getEdgeWeights(const vector &edges, // test the ordering and the outlierWeights function using weights2 - outlier // edge is rejected when projected in a direction that gives weights2 TEST(MFAS, OrderingWeights2) { - MFAS mfas_obj(make_shared>(nodes), getEdgeWeights(edges, weights2)); + MFAS mfas_obj(boost::make_shared>(nodes), getEdgeWeights(edges, weights2)); vector ordered_nodes = mfas_obj.computeOrdering(); @@ -76,7 +80,7 @@ TEST(MFAS, OrderingWeights2) { // weights1 (outlier edge is accepted when projected in a direction that // produces weights1) TEST(MFAS, OrderingWeights1) { - MFAS mfas_obj(make_shared>(nodes), getEdgeWeights(edges, weights1)); + MFAS mfas_obj(boost::make_shared>(nodes), getEdgeWeights(edges, weights1)); vector ordered_nodes = mfas_obj.computeOrdering();