#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_ |
Definition at line 51 of file TranslationRecovery.h.
using gtsam::TranslationRecovery::KeyPair = std::pair<Key, Key> |
Definition at line 53 of file TranslationRecovery.h.
using gtsam::TranslationRecovery::TranslationEdges = std::vector<BinaryMeasurement<Unit3>> |
Definition at line 54 of file TranslationRecovery.h.
TranslationRecovery::TranslationRecovery | ( | const TranslationEdges & | relativeTranslations, |
const LevenbergMarquardtParams & | lmParams = LevenbergMarquardtParams() |
||
) |
Construct a new Translation Recovery object.
relativeTranslations | the 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.
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.
scale | scale for first relative translation which fixes gauge. |
graph | factor graph to which prior is added. |
priorNoiseModel | the 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.
Definition at line 68 of file TranslationRecovery.cpp.
Values TranslationRecovery::initalizeRandomly | ( | ) | const |
Create random initial translations.
Definition at line 91 of file TranslationRecovery.cpp.
Values TranslationRecovery::run | ( | const double | scale = 1.0 | ) | const |
Build and optimize factor graph.
scale | scale for first relative translation which fixes gauge. |
Definition at line 118 of file TranslationRecovery.cpp.
|
static |
Simulate translation direction measurements.
poses | SE(3) ground truth poses stored as Values |
edges | pairs (a,b) for which a measurement w_aZb will be generated. |
Definition at line 140 of file TranslationRecovery.cpp.
|
private |
Definition at line 61 of file TranslationRecovery.h.
|
private |
Definition at line 58 of file TranslationRecovery.h.
Definition at line 65 of file TranslationRecovery.h.