remove unusede ptr member in MFAS

release/4.3a0
Akshay Krishnan 2020-09-20 20:33:37 +00:00
parent 6c14605ed0
commit 1f5c6b8b4b
4 changed files with 11 additions and 30 deletions

View File

@ -2972,6 +2972,7 @@ class BinaryMeasurement {
size_t key1() const;
size_t key2() const;
T measured() const;
gtsam::noiseModel::Base* noiseModel() const;
};
typedef gtsam::BinaryMeasurement<gtsam::Unit3> BinaryMeasurementUnit3;
@ -3118,8 +3119,7 @@ class KeyPairDoubleMap {
};
class MFAS {
MFAS(const gtsam::KeyVector* nodes,
const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
MFAS(const gtsam::BinaryMeasurementsUnit3& relativeTranslations,
const gtsam::Unit3& projectionDirection);
gtsam::KeyPairDoubleMap computeOutlierWeights() const;

View File

@ -113,10 +113,8 @@ void removeNodeFromGraph(const Key node,
graph.erase(node);
}
MFAS::MFAS(const boost::shared_ptr<vector<Key>> nodes,
const TranslationEdges& relativeTranslations,
const Unit3& projectionDirection)
: nodes_(nodes) {
MFAS::MFAS(const TranslationEdges& relativeTranslations,
const Unit3& projectionDirection) {
// Iterate over edges, obtain weights by projecting
// their relativeTranslations along the projection direction
for (const auto& measurement : relativeTranslations) {

View File

@ -22,8 +22,6 @@
#include <gtsam/inference/Key.h>
#include <gtsam/sfm/BinaryMeasurement.h>
#include <boost/shared_ptr.hpp>
#include <memory>
#include <unordered_map>
#include <vector>
@ -58,40 +56,28 @@ class MFAS {
using TranslationEdges = std::vector<BinaryMeasurement<Unit3>>;
private:
// pointer to nodes in the graph
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
std::map<KeyPair, double> edgeWeights_;
public:
/**
* @brief Construct from the nodes in a graph and weighted directed edges
* @brief Construct from the weighted directed edges
* between the nodes. Each node is identified by a Key.
* A shared pointer to the nodes is used as input parameter
* because, MFAS ordering is usually used to compute the ordering of a
* large graph that is already stored in memory. It is unnecessary to make a
* copy of the nodes in this class.
* @param nodes: Nodes in the graph
* @param edgeWeights: weights of edges in the graph
*/
MFAS(const boost::shared_ptr<std::vector<Key>> nodes,
const std::map<KeyPair, double> &edgeWeights)
: nodes_(nodes), edgeWeights_(edgeWeights) {}
MFAS(const std::map<KeyPair, double> &edgeWeights)
: edgeWeights_(edgeWeights) {}
/**
* @brief Constructor to be used in the context of translation averaging.
* Here, the nodes of the graph are cameras in 3D and the edges have a unit
* translation direction between them. The weights of the edges is computed by
* projecting them along a projection direction.
* @param nodes cameras in the epipolar graph (each camera is identified by a
* Key)
* @param relativeTranslations translation directions between the cameras
* @param projectionDirection direction in which edges are to be projected
*/
MFAS(const boost::shared_ptr<std::vector<Key>> nodes,
const TranslationEdges &relativeTranslations,
MFAS(const TranslationEdges &relativeTranslations,
const Unit3 &projectionDirection);
/**
@ -101,7 +87,7 @@ class MFAS {
std::vector<Key> computeOrdering() const;
/**
* @brief Computes the "outlier weights" of the graph. We define the outlier
* @brief Computes the outlier weights of the graph. We define the outlier
* weight of a edge to be zero if the edge is an inlier and the magnitude of
* its edgeWeight if it is an outlier. This function internally calls
* computeOrdering and uses the obtained ordering to identify outlier edges.

View File

@ -7,8 +7,6 @@
#include <gtsam/sfm/MFAS.h>
#include <boost/shared_ptr.hpp>
#include <boost/make_shared.hpp>
#include <CppUnitLite/TestHarness.h>
#include <iostream>
@ -43,14 +41,13 @@ map<MFAS::KeyPair, double> getEdgeWeights(const vector<MFAS::KeyPair> &edges,
for (size_t i = 0; i < edges.size(); i++) {
edgeWeights[edges[i]] = weights[i];
}
cout << "returning edge weights " << edgeWeights.size() << endl;
return edgeWeights;
}
// 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(boost::make_shared<vector<Key>>(nodes), getEdgeWeights(edges, weights2));
MFAS mfas_obj(getEdgeWeights(edges, weights2));
vector<Key> ordered_nodes = mfas_obj.computeOrdering();
@ -80,7 +77,7 @@ TEST(MFAS, OrderingWeights2) {
// weights1 (outlier edge is accepted when projected in a direction that
// produces weights1)
TEST(MFAS, OrderingWeights1) {
MFAS mfas_obj(boost::make_shared<vector<Key>>(nodes), getEdgeWeights(edges, weights1));
MFAS mfas_obj(getEdgeWeights(edges, weights1));
vector<Key> ordered_nodes = mfas_obj.computeOrdering();