changing to boost shared_ptr
parent
1ed651b1a2
commit
6c14605ed0
|
|
@ -3114,16 +3114,16 @@ class KeyPairDoubleMap {
|
|||
size_t size() const;
|
||||
bool empty() const;
|
||||
void clear();
|
||||
size_t at(pair<size_t, size_t>) const;
|
||||
size_t at(const pair<size_t, size_t>& 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 <gtsam/sfm/TranslationRecovery.h>
|
||||
|
|
|
|||
|
|
@ -7,6 +7,8 @@
|
|||
|
||||
#include <gtsam/sfm/MFAS.h>
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
#include <algorithm>
|
||||
#include <map>
|
||||
#include <unordered_map>
|
||||
|
|
@ -111,7 +113,7 @@ void removeNodeFromGraph(const Key node,
|
|||
graph.erase(node);
|
||||
}
|
||||
|
||||
MFAS::MFAS(const std::shared_ptr<vector<Key>>& nodes,
|
||||
MFAS::MFAS(const boost::shared_ptr<vector<Key>> nodes,
|
||||
const TranslationEdges& relativeTranslations,
|
||||
const Unit3& projectionDirection)
|
||||
: nodes_(nodes) {
|
||||
|
|
|
|||
|
|
@ -22,6 +22,8 @@
|
|||
#include <gtsam/inference/Key.h>
|
||||
#include <gtsam/sfm/BinaryMeasurement.h>
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
|
||||
#include <memory>
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
|
|
@ -57,7 +59,7 @@ class MFAS {
|
|||
|
||||
private:
|
||||
// pointer to nodes in the graph
|
||||
const std::shared_ptr<std::vector<Key>> nodes_;
|
||||
const boost::shared_ptr<std::vector<Key>> 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<std::vector<Key>> &nodes,
|
||||
MFAS(const boost::shared_ptr<std::vector<Key>> nodes,
|
||||
const std::map<KeyPair, double> &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<std::vector<Key>> &nodes,
|
||||
MFAS(const boost::shared_ptr<std::vector<Key>> nodes,
|
||||
const TranslationEdges &relativeTranslations,
|
||||
const Unit3 &projectionDirection);
|
||||
|
||||
|
|
|
|||
|
|
@ -6,9 +6,13 @@
|
|||
*/
|
||||
|
||||
#include <gtsam/sfm/MFAS.h>
|
||||
#include <iostream>
|
||||
|
||||
#include <boost/shared_ptr.hpp>
|
||||
#include <boost/make_shared.hpp>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
||||
#include <iostream>
|
||||
|
||||
using namespace std;
|
||||
using namespace gtsam;
|
||||
|
||||
|
|
@ -46,7 +50,7 @@ map<MFAS::KeyPair, double> getEdgeWeights(const vector<MFAS::KeyPair> &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<vector<Key>>(nodes), getEdgeWeights(edges, weights2));
|
||||
MFAS mfas_obj(boost::make_shared<vector<Key>>(nodes), getEdgeWeights(edges, weights2));
|
||||
|
||||
vector<Key> 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<vector<Key>>(nodes), getEdgeWeights(edges, weights1));
|
||||
MFAS mfas_obj(boost::make_shared<vector<Key>>(nodes), getEdgeWeights(edges, weights1));
|
||||
|
||||
vector<Key> ordered_nodes = mfas_obj.computeOrdering();
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue