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>
21 #include <gtsam/nonlinear/Values.h>
23 
24 #include <map>
25 #include <set>
26 #include <utility>
27 #include <vector>
28 
29 namespace 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.
51 class GTSAM_EXPORT TranslationRecovery {
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.
59 
60  // Parameters.
62 
63  const bool use_bilinear_translation_factor_ = false;
64 
65  public:
72  bool use_bilinear_translation_factor = false)
73  : lmParams_(lmParams),
74  use_bilinear_translation_factor_(use_bilinear_translation_factor) {}
75 
79  TranslationRecovery() = default;
80 
88  NonlinearFactorGraph buildGraph(
89  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const;
90 
106  void addPrior(
107  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
108  const double scale,
109  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
111  const SharedNoiseModel &priorNoiseModel =
112  noiseModel::Isotropic::Sigma(3, 0.01)) const;
113 
125  Values initializeRandomly(
126  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
127  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
128  std::mt19937 *rng, const Values &initialValues = Values()) const;
129 
140  Values initializeRandomly(
141  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
142  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
143  const Values &initialValues = Values()) const;
144 
163  Values run(
164  const TranslationEdges &relativeTranslations, const double scale = 1.0,
165  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations = {},
166  const Values &initialValues = Values()) const;
167 
177  static TranslationEdges SimulateMeasurements(
178  const Values &poses, const std::vector<KeyPair> &edges);
179 };
180 } // namespace gtsam
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
gtsam::TranslationRecovery
Definition: TranslationRecovery.h:51
gtsam::TranslationRecovery::TranslationEdges
std::vector< BinaryMeasurement< Unit3 > > TranslationEdges
Definition: TranslationRecovery.h:54
edges
vector< MFAS::KeyPair > edges
Definition: testMFAS.cpp:25
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Values
lmParams
LevenbergMarquardtParams lmParams
Definition: testSmartProjectionRigFactor.cpp:55
Unit3.h
gtsam::TranslationRecovery::lmParams_
LevenbergMarquardtParams lmParams_
Definition: TranslationRecovery.h:61
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam.examples.DogLegOptimizerExample.run
def run(args)
Definition: DogLegOptimizerExample.py:21
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
gtsam::TranslationRecovery::relativeTranslations_
TranslationEdges relativeTranslations_
Definition: TranslationRecovery.h:58
addPrior
graph addPrior(1, Pose2(0, 0, 0), priorNoise)
gtsam::TranslationRecovery::TranslationRecovery
TranslationRecovery(const LevenbergMarquardtParams &lmParams, bool use_bilinear_translation_factor=false)
Construct a new Translation Recovery object.
Definition: TranslationRecovery.h:71
gtsam::BinaryMeasurement
Definition: BinaryMeasurement.h:36
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: SFMdata.h:40
gtsam::Values
Definition: Values.h:65
BinaryMeasurement.h
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
gtsam::TranslationRecovery::KeyPair
std::pair< Key, Key > KeyPair
Definition: TranslationRecovery.h:53
gtsam::scale
static double scale(double x, double a, double b, double t1, double t2)
Scale x from [a, b] to [t1, t2].
Definition: Chebyshev.cpp:35
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
test_TranslationRecovery.SimulateMeasurements
def SimulateMeasurements(gt_poses, graph_edges)
Definition: test_TranslationRecovery.py:20
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:625
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
Values.h
A non-templated config holding any types of Manifold-group elements.


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:18:01