gtsam 4.2.0
gtsam
Loading...
Searching...
No Matches
TranslationRecovery.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
19#include <gtsam/geometry/Unit3.h>
23
24#include <map>
25#include <set>
26#include <utility>
27#include <vector>
28
29namespace gtsam {
30
31// Set up an optimization problem for the unknown translations Ti in the world
32// coordinate frame, given the known camera attitudes wRi with respect to the
33// world frame, and a set of (noisy) translation directions of type Unit3,
34// w_aZb. The measurement equation is
35// w_aZb = Unit3(Tb - Ta) (1)
36// i.e., w_aZb is the translation direction from frame A to B, in world
37// coordinates. Although Unit3 instances live on a manifold, following
38// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the
39// ambient world coordinate frame.
40//
41// It is clear that we cannot recover the scale, nor the absolute position,
42// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing
43// the translations Ta and Tb associated with the first measurement w_aZb,
44// clamping them to their initial values as given to this method. If no initial
45// values are given, we use the origin for Tb and set Tb to make (1) come
46// through, i.e.,
47// Tb = s * wRa * Point3(w_aZb) (2)
48// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two
49// versions are supplied below corresponding to whether we have initial values
50// or not.
52 public:
53 using KeyPair = std::pair<Key, Key>;
54 using TranslationEdges = std::vector<BinaryMeasurement<Unit3>>;
55
56 private:
57 // Translation directions between camera pairs.
58 TranslationEdges relativeTranslations_;
59
60 // Parameters.
62
63 public:
70 : lmParams_(lmParams) {}
71
76
85 const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const;
86
102 void addPrior(
103 const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
104 const double scale,
105 const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
107 const SharedNoiseModel &priorNoiseModel =
108 noiseModel::Isotropic::Sigma(3, 0.01)) const;
109
122 const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
123 const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
124 std::mt19937 *rng, const Values &initialValues = Values()) const;
125
137 const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
138 const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
139 const Values &initialValues = Values()) const;
140
159 Values run(
160 const TranslationEdges &relativeTranslations, const double scale = 1.0,
161 const std::vector<BinaryMeasurement<Point3>> &betweenTranslations = {},
162 const Values &initialValues = Values()) const;
163
173 static TranslationEdges SimulateMeasurements(
174 const Values &poses, const std::vector<KeyPair> &edges);
175};
176} // namespace gtsam
A non-templated config holding any types of Manifold-group elements.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
Global functions in a separate testing namespace.
Definition chartTesting.h:28
noiseModel::Base::shared_ptr SharedNoiseModel
Aliases.
Definition NoiseModel.h:724
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
An isotropic noise model created by specifying a standard devation sigma.
Definition NoiseModel.cpp:597
Parameters for Levenberg-Marquardt optimization.
Definition LevenbergMarquardtParams.h:35
Definition NonlinearFactorGraph.h:55
A non-templated config holding any types of Manifold-group elements.
Definition Values.h:65
Definition BinaryMeasurement.h:36
Definition TranslationRecovery.h:51
NonlinearFactorGraph buildGraph(const std::vector< BinaryMeasurement< Unit3 > > &relativeTranslations) const
Build the factor graph to do the optimization.
Definition TranslationRecovery.cpp:99
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
Definition TranslationRecovery.cpp:216
TranslationRecovery()=default
Default constructor.
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.
Definition TranslationRecovery.cpp:177
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:
Definition TranslationRecovery.cpp:111
TranslationRecovery(const LevenbergMarquardtParams &lmParams)
Construct a new Translation Recovery object.
Definition TranslationRecovery.h:69
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.
Definition TranslationRecovery.cpp:137