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

#include <TranslationRecovery.h>

Public Types

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

Public Member Functions

void addPrior (const double scale, NonlinearFactorGraph *graph, const SharedNoiseModel &priorNoiseModel=noiseModel::Isotropic::Sigma(3, 0.01)) const
 Add priors on ednpoints of first measurement edge. More...
 
NonlinearFactorGraph buildGraph () const
 Build the factor graph to do the optimization. More...
 
Values initalizeRandomly () const
 Create random initial translations. More...
 
Values run (const double scale=1.0) const
 Build and optimize factor graph. More...
 
 TranslationRecovery (const TranslationEdges &relativeTranslations, const LevenbergMarquardtParams &lmParams=LevenbergMarquardtParams())
 Construct a new Translation Recovery object. More...
 

Static Public Member Functions

static TranslationEdges SimulateMeasurements (const Values &poses, const std::vector< KeyPair > &edges)
 Simulate translation direction measurements. More...
 

Private Attributes

LevenbergMarquardtParams params_
 
TranslationEdges relativeTranslations_
 
std::map< Key, std::set< Key > > sameTranslationNodes_
 

Detailed Description

Definition at line 51 of file TranslationRecovery.h.

Member Typedef Documentation

Definition at line 53 of file TranslationRecovery.h.

Definition at line 54 of file TranslationRecovery.h.

Constructor & Destructor Documentation

TranslationRecovery::TranslationRecovery ( const TranslationEdges relativeTranslations,
const LevenbergMarquardtParams lmParams = LevenbergMarquardtParams() 
)

Construct a new Translation Recovery object.

Parameters
relativeTranslationsthe relative translations, in world coordinate frames, vector of BinaryMeasurements of Unit3, where each key of a measurement is a point in 3D.
lmParams(optional) gtsam::LavenbergMarquardtParams that can be used to modify the parameters for the LM optimizer. By default, uses the default LM parameters.

Definition at line 38 of file TranslationRecovery.cpp.

Member Function Documentation

void TranslationRecovery::addPrior ( const double  scale,
NonlinearFactorGraph graph,
const SharedNoiseModel priorNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01) 
) const

Add priors on ednpoints of first measurement edge.

Parameters
scalescale for first relative translation which fixes gauge.
graphfactor graph to which prior is added.
priorNoiseModelthe noise model to use with the prior.

Definition at line 80 of file TranslationRecovery.cpp.

NonlinearFactorGraph TranslationRecovery::buildGraph ( ) const

Build the factor graph to do the optimization.

Returns
NonlinearFactorGraph

Definition at line 68 of file TranslationRecovery.cpp.

Values TranslationRecovery::initalizeRandomly ( ) const

Create random initial translations.

Returns
Values

Definition at line 91 of file TranslationRecovery.cpp.

Values TranslationRecovery::run ( const double  scale = 1.0) const

Build and optimize factor graph.

Parameters
scalescale for first relative translation which fixes gauge.
Returns
Values

Definition at line 118 of file TranslationRecovery.cpp.

TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements ( const Values poses,
const std::vector< KeyPair > &  edges 
)
static

Simulate translation direction measurements.

Parameters
posesSE(3) ground truth poses stored as Values
edgespairs (a,b) for which a measurement w_aZb will be generated.
Returns
TranslationEdges vector of binary measurements where the keys are the cameras and the measurement is the simulated Unit3 translation direction between the cameras.

Definition at line 140 of file TranslationRecovery.cpp.

Member Data Documentation

LevenbergMarquardtParams gtsam::TranslationRecovery::params_
private

Definition at line 61 of file TranslationRecovery.h.

TranslationEdges gtsam::TranslationRecovery::relativeTranslations_
private

Definition at line 58 of file TranslationRecovery.h.

std::map<Key, std::set<Key> > gtsam::TranslationRecovery::sameTranslationNodes_
private

Definition at line 65 of file TranslationRecovery.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:37