#include <TranslationRecovery.h>
|
| 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...
|
| |
| NonlinearFactorGraph | buildGraph (const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations) const |
| | Build the factor graph to do the optimization. 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 | 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 | 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...
|
| |
| | TranslationRecovery ()=default |
| | Default constructor. More...
|
| |
| | TranslationRecovery (const LevenbergMarquardtParams &lmParams, bool use_bilinear_translation_factor=false) |
| | Construct a new Translation Recovery object. More...
|
| |
Definition at line 51 of file TranslationRecovery.h.
◆ KeyPair
◆ TranslationEdges
◆ TranslationRecovery() [1/2]
| gtsam::TranslationRecovery::TranslationRecovery |
( |
const LevenbergMarquardtParams & |
lmParams, |
|
|
bool |
use_bilinear_translation_factor = false |
|
) |
| |
|
inline |
Construct a new Translation Recovery object.
- Parameters
-
| lmParams | parameters for optimization. |
Definition at line 71 of file TranslationRecovery.h.
◆ TranslationRecovery() [2/2]
| gtsam::TranslationRecovery::TranslationRecovery |
( |
| ) |
|
|
default |
◆ addPrior()
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
-
| relativeTranslations | unit translation directions between translations to be estimated |
| scale | scale for first relative translation which fixes gauge. |
| graph | factor graph to which prior is added. |
| betweenTranslations | relative translations (with scale) between 2 points in world coordinate frame known a priori. |
| priorNoiseModel | the noise model to use with the prior. |
Definition at line 119 of file TranslationRecovery.cpp.
◆ buildGraph()
Build the factor graph to do the optimization.
- Parameters
-
| relativeTranslations | unit translation directions between translations to be estimated |
- Returns
- NonlinearFactorGraph
Definition at line 99 of file TranslationRecovery.cpp.
◆ initializeRandomly() [1/2]
Version of initializeRandomly with a fixed seed.
- Parameters
-
| relativeTranslations | unit translation directions between translations to be estimated |
| betweenTranslations | relative translations (with scale) between 2 points in world coordinate frame known a priori. |
| initialValues | (optional) initial values from a prior |
- Returns
- Values
Definition at line 183 of file TranslationRecovery.cpp.
◆ initializeRandomly() [2/2]
Create random initial translations.
- Parameters
-
| relativeTranslations | unit translation directions between translations to be estimated |
| betweenTranslations | relative translations (with scale) between 2 points in world coordinate frame known a priori. |
| rng | random number generator |
| initialValues | (optional) initial values from a prior |
- Returns
- Values
Definition at line 145 of file TranslationRecovery.cpp.
◆ run()
Build and optimize factor graph.
- Parameters
-
| relativeTranslations | the 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). |
| scale | scale for first relative translation which fixes gauge. The scale is only used if betweenTranslations is empty. |
| betweenTranslations | relative translations (with scale) between 2 points in world coordinate frame known a priori. Unlike relativeTranslations, zero-magnitude betweenTranslations are not treated as hard constraints. |
| initialValues | initial values for optimization. Initializes randomly if not provided. |
- Returns
- Values
Definition at line 191 of file TranslationRecovery.cpp.
◆ SimulateMeasurements()
Simulate translation direction measurements.
- Parameters
-
| poses | SE(3) ground truth poses stored as Values |
| edges | pairs (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 230 of file TranslationRecovery.cpp.
◆ lmParams_
◆ relativeTranslations_
◆ use_bilinear_translation_factor_
| const bool gtsam::TranslationRecovery::use_bilinear_translation_factor_ = false |
|
private |
The documentation for this class was generated from the following files: