changes after review - removing positiveEdgeWeights
parent
698ec27e44
commit
b25809d5a3
|
|
@ -1,3 +1,10 @@
|
|||
/**
|
||||
* @file MFAS.cpp
|
||||
* @brief Source file for the MFAS class
|
||||
* @author Akshay Krishnan
|
||||
* @date July 2020
|
||||
*/
|
||||
|
||||
#include <gtsam/sfm/MFAS.h>
|
||||
|
||||
using namespace gtsam;
|
||||
|
|
@ -26,14 +33,20 @@ std::vector<Key> MFAS::computeOrdering() const {
|
|||
FastMap<Key, int> ordered_positions; // map from node to its position in the output order
|
||||
|
||||
// populate neighbors and weights
|
||||
// Since the weights could be obtained by projection, they can be either
|
||||
// negative or positive. Ideally, the weights should be positive in the
|
||||
// direction of the edge. So, we define the direction of the edge as
|
||||
// edge.first -> edge.second if weight is positive and
|
||||
// edge.second -> edge.first if weight is negative. Once we know the
|
||||
// direction, we only use the magnitude of the weights.
|
||||
for (auto it = edgeWeights_.begin(); it != edgeWeights_.end(); it++) {
|
||||
const KeyPair &edge = it->first;
|
||||
const double weight = it->second;
|
||||
Key edge_source = weight >= 0 ? edge.first : edge.second;
|
||||
Key edge_dest = weight >= 0 ? edge.second : edge.first;
|
||||
|
||||
in_weights[edge_dest] += weight;
|
||||
out_weights[edge_source] += weight;
|
||||
in_weights[edge_dest] += std::abs(weight);
|
||||
out_weights[edge_source] += std::abs(weight);
|
||||
in_neighbors[edge_dest].push_back(edge_source);
|
||||
out_neighbors[edge_source].push_back(edge_dest);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -11,6 +11,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* @file MFAS.h
|
||||
* @brief MFAS class to solve Minimum Feedback Arc Set graph problem
|
||||
* @author Akshay Krishnan
|
||||
* @date July 2020
|
||||
*/
|
||||
|
||||
#include <gtsam/geometry/Unit3.h>
|
||||
#include <gtsam/inference/Key.h>
|
||||
|
||||
|
|
@ -29,13 +36,24 @@ namespace gtsam {
|
|||
Given a weighted directed graph, the objective in a Minimum feedback arc set
|
||||
problem is to obtain a directed acyclic graph by removing
|
||||
edges such that the total weight of removed edges is minimum.
|
||||
|
||||
Although MFAS is a general graph problem and can be applied in many areas, this
|
||||
classed was designed for the purpose of outlier rejection in a
|
||||
translation averaging for SfM setting. For more details, refer to the above paper.
|
||||
The nodes of the graph in this context represents cameras in 3D and the edges
|
||||
between them represent unit translations in the world coordinate frame, i.e
|
||||
w_aZb is the unit translation from a to b expressed in the world coordinate frame.
|
||||
The weights for the edges are obtained by projecting the unit translations in a
|
||||
projection direction.
|
||||
@addtogroup SFM
|
||||
*/
|
||||
class MFAS {
|
||||
public:
|
||||
// used to represent edges between two nodes in the graph
|
||||
// used to represent edges between two nodes in the graph. When used in
|
||||
// translation averaging for global SfM
|
||||
using KeyPair = std::pair<Key, Key>;
|
||||
using TranslationEdges = std::map<KeyPair, Unit3>;
|
||||
|
||||
private:
|
||||
// pointer to nodes in the graph
|
||||
const std::shared_ptr<std::vector<Key>> nodes_;
|
||||
|
|
@ -47,44 +65,45 @@ class MFAS {
|
|||
public:
|
||||
/**
|
||||
* @brief Construct from the nodes in a graph and weighted directed edges
|
||||
* between the graph. A shared pointer to the nodes is used as input parameter.
|
||||
* This is because, MFAS ordering is usually used to compute the ordering of a
|
||||
* large graph that is already stored in memory. It is unnecessary to copy the
|
||||
* set of nodes in this class.
|
||||
* 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 make a
|
||||
* copy of the nodes in this class.
|
||||
* @param nodes: Nodes in the graph
|
||||
* @param edgeWeights: weights of edges in the graph (map from pair of keys
|
||||
* to signed double)
|
||||
* @param edgeWeights: weights of edges in the graph
|
||||
*/
|
||||
MFAS(const std::shared_ptr<std::vector<Key>> &nodes,
|
||||
const std::map<KeyPair, double> &edgeWeights) :
|
||||
nodes_(nodes), edgeWeights_(edgeWeights) {}
|
||||
|
||||
/**
|
||||
* @brief Constructor for using in the context of translation averaging. Here,
|
||||
* @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 Nodes in the graph
|
||||
* @param relativeTranslations translation directions between nodes
|
||||
* @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 std::shared_ptr<std::vector<Key>> &nodes,
|
||||
const TranslationEdges& relativeTranslations,
|
||||
const Unit3 &projectionDirection);
|
||||
|
||||
/**
|
||||
* @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.
|
||||
* @return outlierWeights: map from an edge to its outlier weight.
|
||||
*/
|
||||
std::map<KeyPair, double> computeOutlierWeights() const;
|
||||
|
||||
/**
|
||||
* @brief Computes the 1D MFAS ordering of nodes in the graph
|
||||
* @return orderedNodes: vector of nodes in the obtained order
|
||||
*/
|
||||
std::vector<Key> computeOrdering() const;
|
||||
|
||||
/**
|
||||
* @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.
|
||||
* @return outlierWeights: map from an edge to its outlier weight.
|
||||
*/
|
||||
std::map<KeyPair, double> computeOutlierWeights() const;
|
||||
};
|
||||
|
||||
} // namespace gtsam
|
||||
|
|
|
|||
|
|
@ -1,3 +1,10 @@
|
|||
/**
|
||||
* @file testMFAS.cpp
|
||||
* @brief Unit tests for the MFAS class
|
||||
* @author Akshay Krishnan
|
||||
* @date July 2020
|
||||
*/
|
||||
|
||||
#include <gtsam/sfm/MFAS.h>
|
||||
#include <iostream>
|
||||
#include <CppUnitLite/TestHarness.h>
|
||||
|
|
|
|||
Loading…
Reference in New Issue