GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Public Types | Public Member Functions | Static Public Member Functions | List of all members
gtsam::TranslationRecovery Class Reference

Public Types

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

Public Member Functions

 TranslationRecovery (const LevenbergMarquardtParams &lmParams)
 Construct a new Translation Recovery object. More...
 
 TranslationRecovery ()=default
 Default constructor.
 
NonlinearFactorGraph buildGraph (const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations) const
 Build the factor graph to do the optimization. More...
 
void addPrior (const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations, const double scale, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations, NonlinearFactorGraph *graph, const SharedNoiseModel &priorNoiseModel=noiseModel::Isotropic::Sigma(3, 0.01)) const
 Add 3 factors to the graph: More...
 
Values initializeRandomly (const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations, std::mt19937 *rng, const Values &initialValues=Values()) const
 Create random initial translations. More...
 
Values initializeRandomly (const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations, const Values &initialValues=Values()) const
 Version of initializeRandomly with a fixed seed. More...
 
Values run (const TranslationEdges &relativeTranslations, const double scale=1.0, const std::vector< BinaryMeasurement< Point3 >> &betweenTranslations={}, const Values &initialValues=Values()) const
 Build and optimize factor graph. More...
 

Static Public Member Functions

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

Constructor & Destructor Documentation

◆ TranslationRecovery()

gtsam::TranslationRecovery::TranslationRecovery ( const LevenbergMarquardtParams lmParams)
inline

Construct a new Translation Recovery object.

Parameters
lmParamsparameters for optimization.

Member Function Documentation

◆ addPrior()

void gtsam::TranslationRecovery::addPrior ( const std::vector< BinaryMeasurement< Unit3 >> &  relativeTranslations,
const double  scale,
const std::vector< BinaryMeasurement< Point3 >> &  betweenTranslations,
NonlinearFactorGraph graph,
const SharedNoiseModel priorNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01) 
) const

Add 3 factors to the graph:

  • A prior on the first point to lie at (0, 0, 0)
  • If betweenTranslations is non-empty, between factors provided by it.
  • If betweenTranslations is empty, a prior on scale of the first relativeTranslations edge.
Parameters
relativeTranslationsunit translation directions between translations to be estimated
scalescale for first relative translation which fixes gauge.
graphfactor graph to which prior is added.
betweenTranslationsrelative translations (with scale) between 2 points in world coordinate frame known a priori.
priorNoiseModelthe noise model to use with the prior.

◆ buildGraph()

NonlinearFactorGraph gtsam::TranslationRecovery::buildGraph ( const std::vector< BinaryMeasurement< Unit3 >> &  relativeTranslations) const

Build the factor graph to do the optimization.

Parameters
relativeTranslationsunit translation directions between translations to be estimated
Returns
NonlinearFactorGraph

◆ initializeRandomly() [1/2]

Values gtsam::TranslationRecovery::initializeRandomly ( const std::vector< BinaryMeasurement< Unit3 >> &  relativeTranslations,
const std::vector< BinaryMeasurement< Point3 >> &  betweenTranslations,
std::mt19937 *  rng,
const Values initialValues = Values() 
) const

Create random initial translations.

Parameters
relativeTranslationsunit translation directions between translations to be estimated
betweenTranslationsrelative translations (with scale) between 2 points in world coordinate frame known a priori.
rngrandom number generator
intialValues(optional) initial values from a prior
Returns
Values

◆ initializeRandomly() [2/2]

Values gtsam::TranslationRecovery::initializeRandomly ( const std::vector< BinaryMeasurement< Unit3 >> &  relativeTranslations,
const std::vector< BinaryMeasurement< Point3 >> &  betweenTranslations,
const Values initialValues = Values() 
) const

Version of initializeRandomly with a fixed seed.

Parameters
relativeTranslationsunit translation directions between translations to be estimated
betweenTranslationsrelative translations (with scale) between 2 points in world coordinate frame known a priori.
initialValues(optional) initial values from a prior
Returns
Values

◆ run()

Values gtsam::TranslationRecovery::run ( const TranslationEdges &  relativeTranslations,
const double  scale = 1.0,
const std::vector< BinaryMeasurement< Point3 >> &  betweenTranslations = {},
const Values initialValues = Values() 
) const

Build and optimize factor graph.

Parameters
relativeTranslationsthe relative translations, in world coordinate frames, vector of BinaryMeasurements of Unit3, where each key of a measurement is a point in 3D. If a relative translation magnitude is zero, it is treated as a hard same-point constraint (the result of all nodes connected by a zero-magnitude edge will be the same).
scalescale for first relative translation which fixes gauge. The scale is only used if betweenTranslations is empty.
betweenTranslationsrelative translations (with scale) between 2 points in world coordinate frame known a priori. Unlike relativeTranslations, zero-magnitude betweenTranslations are not treated as hard constraints.
initialValuesintial values for optimization. Initializes randomly if not provided.
Returns
Values

◆ SimulateMeasurements()

static TranslationEdges gtsam::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.

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