|
KeyVector | computeOrdering () const |
| Computes the 1D MFAS ordering of nodes in the graph. More...
|
|
std::map< KeyPair, double > | computeOutlierWeights () const |
| 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. More...
|
|
| MFAS (const std::map< KeyPair, double > &edgeWeights) |
| Construct from the weighted directed edges between the nodes. Each node is identified by a Key. More...
|
|
| MFAS (const TranslationEdges &relativeTranslations, const Unit3 &projectionDirection) |
| 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. More...
|
|
The MFAS class to solve a Minimum feedback arc set (MFAS) problem. We implement the solution from: Kyle Wilson and Noah Snavely, "Robust Global Translations with 1DSfM", Proceedings of the European Conference on Computer Vision, ECCV 2014
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.
Definition at line 51 of file MFAS.h.