Public Types | Public Member Functions | Private Attributes | List of all members
gtsam::MFAS Class Reference

#include <MFAS.h>

Public Types

using KeyPair = std::pair< Key, Key >
 
using TranslationEdges = std::vector< BinaryMeasurement< Unit3 > >
 

Public Member Functions

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...
 

Private Attributes

std::map< KeyPair, double > edgeWeights_
 

Detailed Description

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.

Member Typedef Documentation

◆ KeyPair

using gtsam::MFAS::KeyPair = std::pair<Key, Key>

Definition at line 55 of file MFAS.h.

◆ TranslationEdges

Definition at line 56 of file MFAS.h.

Constructor & Destructor Documentation

◆ MFAS() [1/2]

gtsam::MFAS::MFAS ( const std::map< KeyPair, double > &  edgeWeights)
inline

Construct from the weighted directed edges between the nodes. Each node is identified by a Key.

Parameters
edgeWeightsweights of edges in the graph

Definition at line 69 of file MFAS.h.

◆ MFAS() [2/2]

MFAS::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.

Parameters
relativeTranslationstranslation directions between the cameras
projectionDirectiondirection in which edges are to be projected

Definition at line 114 of file MFAS.cpp.

Member Function Documentation

◆ computeOrdering()

KeyVector MFAS::computeOrdering ( ) const

Computes the 1D MFAS ordering of nodes in the graph.

Returns
orderedNodes: vector of nodes in the obtained order

Definition at line 124 of file MFAS.cpp.

◆ computeOutlierWeights()

map< MFAS::KeyPair, double > MFAS::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.

Returns
outlierWeights: map from an edge to its outlier weight.

Definition at line 141 of file MFAS.cpp.

Member Data Documentation

◆ edgeWeights_

std::map<KeyPair, double> gtsam::MFAS::edgeWeights_
private

Definition at line 61 of file MFAS.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:46:23