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 <map>
20 #include <set>
21 #include <utility>
22 #include <vector>
23 
24 #include <gtsam/geometry/Unit3.h>
26 #include <gtsam/nonlinear/Values.h>
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.
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 used by the LM Optimizer.
62 
63  // Map from a key in the graph to a set of keys that share the same
64  // translation.
65  std::map<Key, std::set<Key>> sameTranslationNodes_;
66 
67  public:
79  const TranslationEdges &relativeTranslations,
81 
88 
96  void addPrior(const double scale, NonlinearFactorGraph *graph,
97  const SharedNoiseModel &priorNoiseModel =
98  noiseModel::Isotropic::Sigma(3, 0.01)) const;
99 
105  Values initalizeRandomly() const;
106 
113  Values run(const double scale = 1.0) const;
114 
125  const Values &poses, const std::vector<KeyPair> &edges);
126 };
127 } // namespace gtsam
vector< MFAS::KeyPair > edges
Definition: testMFAS.cpp:25
A non-templated config holding any types of Manifold-group elements.
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.
std::map< Key, std::set< Key > > sameTranslationNodes_
NonlinearFactorGraph graph
Values run(const double scale=1.0) const
Build and optimize factor graph.
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
traits
Definition: chartTesting.h:28
TranslationRecovery(const TranslationEdges &relativeTranslations, const LevenbergMarquardtParams &lmParams=LevenbergMarquardtParams())
Construct a new Translation Recovery object.
NonlinearFactorGraph buildGraph() const
Build the factor graph to do the optimization.
LevenbergMarquardtParams lmParams
LevenbergMarquardtParams params_
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
std::vector< BinaryMeasurement< Unit3 >> TranslationEdges
std::pair< Key, Key > KeyPair
Binary measurement represents a measurement between two keys in a graph. A binary measurement is simi...
TranslationEdges relativeTranslations_
Values initalizeRandomly() const
Create random initial translations.
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:567


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:09