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>
28 #include <gtsam/nonlinear/Values.h>
32 #include <gtsam/slam/PriorFactor.h>
33 #include <gtsam/slam/expressions.h>
34 
35 #include <set>
36 #include <utility>
37 
38 using namespace gtsam;
39 using namespace std;
40 
41 // In Wrappers we have no access to this so have a default ready.
42 static std::mt19937 kRandomNumberGenerator(42);
43 
44 // Some relative translations may be zero. We treat nodes that have a zero
45 // relativeTranslation as a single node.
46 // A DSFMap is used to find sets of nodes that have a zero relative
47 // translation. Add the nodes in each edge to the DSFMap, and merge nodes that
48 // are connected by a zero relative translation.
50  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) {
51  DSFMap<Key> sameTranslationDSF;
52  for (const auto &edge : relativeTranslations) {
53  Key key1 = sameTranslationDSF.find(edge.key1());
54  Key key2 = sameTranslationDSF.find(edge.key2());
55  if (key1 != key2 && edge.measured().equals(Unit3(0.0, 0.0, 0.0))) {
56  sameTranslationDSF.merge(key1, key2);
57  }
58  }
59  return sameTranslationDSF;
60 }
61 
62 // Removes zero-translation edges from measurements, and combines the nodes in
63 // these edges into a single node.
64 template <typename T>
65 std::vector<BinaryMeasurement<T>> removeSameTranslationNodes(
66  const std::vector<BinaryMeasurement<T>> &edges,
67  const DSFMap<Key> &sameTranslationDSFMap) {
68  std::vector<BinaryMeasurement<T>> newEdges;
69  for (const auto &edge : edges) {
70  Key key1 = sameTranslationDSFMap.find(edge.key1());
71  Key key2 = sameTranslationDSFMap.find(edge.key2());
72  if (key1 == key2) continue;
73  newEdges.emplace_back(key1, key2, edge.measured(), edge.noiseModel());
74  }
75  return newEdges;
76 }
77 
78 // Adds nodes that were not optimized for because they were connected
79 // to another node with a zero-translation edge in the input.
81  const DSFMap<Key> &sameTranslationDSFMap) {
82  Values final_result = result;
83  // Nodes that were not optimized are stored in sameTranslationNodes_ as a map
84  // from a key that was optimized to keys that were not optimized. Iterate over
85  // map and add results for keys not optimized.
86  for (const auto &optimizedAndDuplicateKeys : sameTranslationDSFMap.sets()) {
87  Key optimizedKey = optimizedAndDuplicateKeys.first;
88  std::set<Key> duplicateKeys = optimizedAndDuplicateKeys.second;
89  // Add the result for the duplicate key if it does not already exist.
90  for (const Key duplicateKey : duplicateKeys) {
91  if (final_result.exists(duplicateKey)) continue;
92  final_result.insert<Point3>(duplicateKey,
93  final_result.at<Point3>(optimizedKey));
94  }
95  }
96  return final_result;
97 }
98 
100  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations) const {
102 
103  // Add translation factors for input translation directions.
104  uint64_t i = 0;
105  for (auto edge : relativeTranslations) {
106  if (use_bilinear_translation_factor_) {
108  edge.key1(), edge.key2(), Symbol('S', i), edge.measured(),
109  edge.noiseModel());
110  } else {
112  edge.key1(), edge.key2(), edge.measured(), edge.noiseModel());
113  }
114  i++;
115  }
116  return graph;
117 }
118 
120  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
121  const double scale,
122  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
124  const SharedNoiseModel &priorNoiseModel) const {
125  auto edge = relativeTranslations.begin();
126  if (edge == relativeTranslations.end()) return;
127  graph->emplace_shared<PriorFactor<Point3>>(edge->key1(), Point3(0, 0, 0),
128  priorNoiseModel);
129 
130  // Add a scale prior only if no other between factors were added.
131  if (betweenTranslations.empty()) {
133  edge->key2(), scale * edge->measured().point3(), edge->noiseModel());
134  return;
135  }
136 
137  // Add between factors for optional relative translations.
138  for (auto prior_edge : betweenTranslations) {
140  prior_edge.key1(), prior_edge.key2(), prior_edge.measured(),
141  prior_edge.noiseModel());
142  }
143 }
144 
146  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
147  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
148  std::mt19937 *rng, const Values &initialValues) const {
149  uniform_real_distribution<double> randomVal(-1, 1);
150  // Create a lambda expression that checks whether value exists and randomly
151  // initializes if not.
152  Values initial;
153  auto insert = [&](Key j) {
154  if (initial.exists(j)) return;
155  if (initialValues.exists(j)) {
156  initial.insert<Point3>(j, initialValues.at<Point3>(j));
157  } else {
158  initial.insert<Point3>(
159  j, Point3(randomVal(*rng), randomVal(*rng), randomVal(*rng)));
160  }
161  // Assumes all nodes connected by zero-edges have the same initialization.
162  };
163 
164  // Loop over measurements and add a random translation
165  for (auto edge : relativeTranslations) {
166  insert(edge.key1());
167  insert(edge.key2());
168  }
169  // There may be nodes in betweenTranslations that do not have a measurement.
170  for (auto edge : betweenTranslations) {
171  insert(edge.key1());
172  insert(edge.key2());
173  }
174 
175  if (use_bilinear_translation_factor_) {
176  for (uint64_t i = 0; i < relativeTranslations.size(); i++) {
177  initial.insert<Vector1>(Symbol('S', i), Vector1(1.0));
178  }
179  }
180  return initial;
181 }
182 
184  const std::vector<BinaryMeasurement<Unit3>> &relativeTranslations,
185  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
186  const Values &initialValues) const {
187  return initializeRandomly(relativeTranslations, betweenTranslations,
188  &kRandomNumberGenerator, initialValues);
189 }
190 
192  const TranslationEdges &relativeTranslations, const double scale,
193  const std::vector<BinaryMeasurement<Point3>> &betweenTranslations,
194  const Values &initialValues) const {
195  // Find edges that have a zero-translation, and recompute relativeTranslations
196  // and betweenTranslations by retaining only one node for every zero-edge.
197  DSFMap<Key> sameTranslationDSFMap =
198  getSameTranslationDSFMap(relativeTranslations);
199  const TranslationEdges nonzeroRelativeTranslations =
200  removeSameTranslationNodes(relativeTranslations, sameTranslationDSFMap);
201  const std::vector<BinaryMeasurement<Point3>> nonzeroBetweenTranslations =
202  removeSameTranslationNodes(betweenTranslations, sameTranslationDSFMap);
203 
204  // Create graph of translation factors.
205  NonlinearFactorGraph graph = buildGraph(nonzeroRelativeTranslations);
206 
207  // Add global frame prior and scale (either from betweenTranslations or
208  // scale).
209  addPrior(nonzeroRelativeTranslations, scale, nonzeroBetweenTranslations,
210  &graph);
211 
212  // Uses initial values from params if provided.
213  Values initial = initializeRandomly(
214  nonzeroRelativeTranslations, nonzeroBetweenTranslations, initialValues);
215 
216  // If there are no valid edges, but zero-distance edges exist, initialize one
217  // of the nodes in a connected component of zero-distance edges.
218  if (initial.empty() && !sameTranslationDSFMap.sets().empty()) {
219  for (const auto &optimizedAndDuplicateKeys : sameTranslationDSFMap.sets()) {
220  Key optimizedKey = optimizedAndDuplicateKeys.first;
221  initial.insert<Point3>(optimizedKey, Point3(0, 0, 0));
222  }
223  }
224 
225  LevenbergMarquardtOptimizer lm(graph, initial, lmParams_);
226  Values result = lm.optimize();
227  return addSameTranslationNodes(result, sameTranslationDSFMap);
228 }
229 
231  const Values &poses, const vector<KeyPair> &edges) {
232  auto edgeNoiseModel = noiseModel::Isotropic::Sigma(3, 0.01);
233  TranslationEdges relativeTranslations;
234  for (auto edge : edges) {
235  Key a, b;
236  tie(a, b) = edge;
237  const Pose3 wTa = poses.at<Pose3>(a), wTb = poses.at<Pose3>(b);
238  const Point3 Ta = wTa.translation(), Tb = wTb.translation();
239  const Unit3 w_aZb(Tb - Ta);
240  relativeTranslations.emplace_back(a, b, w_aZb, edgeNoiseModel);
241  }
242  return relativeTranslations;
243 }
key1
const Symbol key1('v', 1)
gtsam::Vector1
Eigen::Matrix< double, 1, 1 > Vector1
Definition: Vector.h:41
gtsam::Values::exists
bool exists(Key j) const
Definition: Values.cpp:93
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
getSameTranslationDSFMap
DSFMap< Key > getSameTranslationDSFMap(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations)
Definition: TranslationRecovery.cpp:49
gtsam::TranslationRecovery::TranslationEdges
std::vector< BinaryMeasurement< Unit3 > > TranslationEdges
Definition: TranslationRecovery.h:54
TranslationFactor.h
Binary factor for a relative translation direction measurement.
edges
vector< MFAS::KeyPair > edges
Definition: testMFAS.cpp:25
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
initial
Values initial
Definition: OdometryOptimize.cpp:2
gtsam::Symbol::equals
bool equals(const Symbol &expected, double tol=0.0) const
Check equality.
Definition: Symbol.cpp:54
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::TranslationRecovery::buildGraph
NonlinearFactorGraph buildGraph(const std::vector< BinaryMeasurement< Unit3 >> &relativeTranslations) const
Build the factor graph to do the optimization.
Definition: TranslationRecovery.cpp:99
Point3.h
3D Point
removeSameTranslationNodes
std::vector< BinaryMeasurement< T > > removeSameTranslationNodes(const std::vector< BinaryMeasurement< T >> &edges, const DSFMap< Key > &sameTranslationDSFMap)
Definition: TranslationRecovery.cpp:65
result
Values result
Definition: OdometryOptimize.cpp:8
Unit3.h
addSameTranslationNodes
Values addSameTranslationNodes(const Values &result, const DSFMap< Key > &sameTranslationDSFMap)
Definition: TranslationRecovery.cpp:80
gtsam::TranslationRecovery::initializeRandomly
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:145
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
key2
const Symbol key2('v', 2)
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
DSFMap.h
Allow for arbitrary type in DSF.
BetweenFactor.h
gtsam::kRandomNumberGenerator
static std::mt19937 kRandomNumberGenerator(42)
gtsam::DSFMap::sets
std::map< KEY, Set > sets() const
return all sets, i.e. a partition of all elements
Definition: DSFMap.h:105
gtsam::Pose3
Definition: Pose3.h:37
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:308
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::TranslationRecovery::SimulateMeasurements
static TranslationEdges SimulateMeasurements(const Values &poses, const std::vector< KeyPair > &edges)
Simulate translation direction measurements.
Definition: TranslationRecovery.cpp:230
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
addPrior
graph addPrior(1, Pose2(0, 0, 0), priorNoise)
gtsam::TranslationRecovery::addPrior
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:119
gtsam::DSFMap::find
KEY find(const KEY &key) const
Given key, find the representative key for the set in which it lives.
Definition: DSFMap.h:81
gtsam::DSFMap::merge
void merge(const KEY &x, const KEY &y)
Merge two sets.
Definition: DSFMap.h:87
gtsam::DSFMap
Definition: DSFMap.h:34
NonlinearFactor.h
Non-linear factor base classes.
gtsam::b
const G & b
Definition: Group.h:79
TranslationRecovery.h
Recovering translations in an epipolar graph when rotations are given.
gtsam::BinaryMeasurement
Definition: BinaryMeasurement.h:36
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::TranslationRecovery::run
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:191
gtsam
traits
Definition: SFMdata.h:40
PriorFactor.h
NoiseModel.h
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
expressions.h
Common expressions for solving geometry/slam/sfm problems.
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
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
ExpressionFactor.h
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
initial
Definition: testScenarioRunner.cpp:148
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:624
uint64_t
unsigned __int64 uint64_t
Definition: ms_stdint.h:95
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
insert
A insert(1, 2)=0
gtsam::BilinearAngleTranslationFactor
Definition: TranslationFactor.h:104
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Values.h
A non-templated config holding any types of Manifold-group elements.
Pose3.h
3D Pose
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153
gtsam::Symbol
Definition: inference/Symbol.h:37
gtsam::TranslationFactor
Definition: TranslationFactor.h:41
gtsam::BetweenFactor
Definition: BetweenFactor.h:40


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:09:17