TranslationRecovery.cpp
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/base/DSFMap.h>
20 #include <gtsam/geometry/Point3.h>
21 #include <gtsam/geometry/Pose3.h>
22 #include <gtsam/geometry/Unit3.h>
27 #include <gtsam/nonlinear/Values.h>
30 #include <gtsam/slam/PriorFactor.h>
31 
32 #include <set>
33 #include <utility>
34 
35 using namespace gtsam;
36 using namespace std;
37 
39  const TranslationRecovery::TranslationEdges &relativeTranslations,
41  : params_(lmParams) {
42  // Some relative translations may be zero. We treat nodes that have a zero
43  // relativeTranslation as a single node.
44 
45  // A DSFMap is used to find sets of nodes that have a zero relative
46  // translation. Add the nodes in each edge to the DSFMap, and merge nodes that
47  // are connected by a zero relative translation.
48  DSFMap<Key> sameTranslationDSF;
49  for (const auto &edge : relativeTranslations) {
50  Key key1 = sameTranslationDSF.find(edge.key1());
51  Key key2 = sameTranslationDSF.find(edge.key2());
52  if (key1 != key2 && edge.measured().equals(Unit3(0.0, 0.0, 0.0))) {
53  sameTranslationDSF.merge(key1, key2);
54  }
55  }
56  // Use only those edges for which two keys have a distinct root in the DSFMap.
57  for (const auto &edge : relativeTranslations) {
58  Key key1 = sameTranslationDSF.find(edge.key1());
59  Key key2 = sameTranslationDSF.find(edge.key2());
60  if (key1 == key2) continue;
61  relativeTranslations_.emplace_back(key1, key2, edge.measured(),
62  edge.noiseModel());
63  }
64  // Store the DSF map for post-processing results.
65  sameTranslationNodes_ = sameTranslationDSF.sets();
66 }
67 
70 
71  // Add all relative translation edges
72  for (auto edge : relativeTranslations_) {
73  graph.emplace_shared<TranslationFactor>(edge.key1(), edge.key2(),
74  edge.measured(), edge.noiseModel());
75  }
76 
77  return graph;
78 }
79 
81  const double scale, NonlinearFactorGraph *graph,
82  const SharedNoiseModel &priorNoiseModel) const {
83  auto edge = relativeTranslations_.begin();
84  if (edge == relativeTranslations_.end()) return;
85  graph->emplace_shared<PriorFactor<Point3> >(edge->key1(), Point3(0, 0, 0),
86  priorNoiseModel);
88  edge->key2(), scale * edge->measured().point3(), edge->noiseModel());
89 }
90 
92  // Create a lambda expression that checks whether value exists and randomly
93  // initializes if not.
95  auto insert = [&initial](Key j) {
96  if (!initial.exists(j)) {
97  initial.insert<Point3>(j, Vector3::Random());
98  }
99  };
100 
101  // Loop over measurements and add a random translation
102  for (auto edge : relativeTranslations_) {
103  insert(edge.key1());
104  insert(edge.key2());
105  }
106 
107  // If there are no valid edges, but zero-distance edges exist, initialize one
108  // of the nodes in a connected component of zero-distance edges.
109  if (initial.empty() && !sameTranslationNodes_.empty()) {
110  for (const auto &optimizedAndDuplicateKeys : sameTranslationNodes_) {
111  Key optimizedKey = optimizedAndDuplicateKeys.first;
112  initial.insert<Point3>(optimizedKey, Point3(0, 0, 0));
113  }
114  }
115  return initial;
116 }
117 
118 Values TranslationRecovery::run(const double scale) const {
119  auto graph = buildGraph();
120  addPrior(scale, &graph);
121  const Values initial = initalizeRandomly();
123  Values result = lm.optimize();
124 
125  // Nodes that were not optimized are stored in sameTranslationNodes_ as a map
126  // from a key that was optimized to keys that were not optimized. Iterate over
127  // map and add results for keys not optimized.
128  for (const auto &optimizedAndDuplicateKeys : sameTranslationNodes_) {
129  Key optimizedKey = optimizedAndDuplicateKeys.first;
130  std::set<Key> duplicateKeys = optimizedAndDuplicateKeys.second;
131  // Add the result for the duplicate key if it does not already exist.
132  for (const Key duplicateKey : duplicateKeys) {
133  if (result.exists(duplicateKey)) continue;
134  result.insert<Point3>(duplicateKey, result.at<Point3>(optimizedKey));
135  }
136  }
137  return result;
138 }
139 
141  const Values &poses, const vector<KeyPair> &edges) {
142  auto edgeNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01);
143  TranslationEdges relativeTranslations;
144  for (auto edge : edges) {
145  Key a, b;
146  tie(a, b) = edge;
147  const Pose3 wTa = poses.at<Pose3>(a), wTb = poses.at<Pose3>(b);
148  const Point3 Ta = wTa.translation(), Tb = wTb.translation();
149  const Unit3 w_aZb(Tb - Ta);
150  relativeTranslations.emplace_back(a, b, w_aZb, edgeNoiseModel);
151  }
152  return relativeTranslations;
153 }
vector< MFAS::KeyPair > edges
Definition: testMFAS.cpp:25
A insert(1, 2)=0
bool exists(Key j) const
Definition: Values.cpp:104
virtual const Values & optimize()
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
void merge(const KEY &x, const KEY &y)
Merge two sets.
Definition: DSFMap.h:87
void insert(Key j, const Value &val)
Definition: Values.cpp:140
KEY find(const KEY &key) const
Given key, find the representative key for the set in which it lives.
Definition: DSFMap.h:81
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_
Values initial
Definition: Half.h:150
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
bool empty() const
Definition: Values.h:239
NonlinearFactorGraph graph
Values run(const double scale=1.0) const
Build and optimize factor graph.
Array33i a
const Symbol key1('v', 1)
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&...args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:172
Values result
const ValueType at(Key j) const
Definition: Values-inl.h:342
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
const G & b
Definition: Group.h:83
Binary factor for a relative translation direction measurement.
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.
Non-linear factor base classes.
LevenbergMarquardtParams lmParams
const Symbol key2('v', 2)
LevenbergMarquardtParams params_
3D Point
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
Allow for arbitrary type in DSF.
std::vector< BinaryMeasurement< Unit3 >> TranslationEdges
Recovering translations in an epipolar graph when rotations are given.
Vector3 Point3
Definition: Point3.h:35
std::map< KEY, Set > sets() const
return all sets, i.e. a partition of all elements
Definition: DSFMap.h:105
3D Pose
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
TranslationEdges relativeTranslations_
std::ptrdiff_t j
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