GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
InitializePose3.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, 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 
21 #pragma once
22 
23 #include <gtsam/geometry/Rot3.h>
27 
28 #include <map>
29 #include <vector>
30 
31 namespace gtsam {
32 
33 typedef std::map<Key, std::vector<size_t> > KeyVectorMap;
34 typedef std::map<Key, Rot3> KeyRotMap;
35 
36 struct GTSAM_EXPORT InitializePose3 {
37  static GaussianFactorGraph buildLinearOrientationGraph(
38  const NonlinearFactorGraph& g);
39 
40  static Values normalizeRelaxedRotations(const VectorValues& relaxedRot3);
41 
45  static Values computeOrientationsChordal(
46  const NonlinearFactorGraph& pose3Graph);
47 
51  static Values computeOrientationsGradient(
52  const NonlinearFactorGraph& pose3Graph, const Values& givenGuess,
53  size_t maxIter = 10000, const bool setRefFrame = true);
54 
55  static void createSymbolicGraph(const NonlinearFactorGraph& pose3Graph,
56  KeyVectorMap* adjEdgesMap,
57  KeyRotMap* factorId2RotMap);
58 
59  static Vector3 gradientTron(const Rot3& R1, const Rot3& R2, const double a,
60  const double b);
61 
66  static NonlinearFactorGraph buildPose3graph(
67  const NonlinearFactorGraph& graph);
68 
72  static Values computePoses(const Values& initialRot,
73  NonlinearFactorGraph* poseGraph,
74  bool singleIter = true);
75 
80  static Values initializeOrientations(const NonlinearFactorGraph& graph);
81 
87  static Values initialize(const NonlinearFactorGraph& graph,
88  const Values& givenGuess, bool useGradient = false);
89 
91  static Values initialize(const NonlinearFactorGraph& graph);
92 };
93 } // end of namespace gtsam
Definition: InitializePose3.h:36
Factor Graph consisting of non-linear factors.
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
Definition: VectorValues.h:74
Factor Graph Values.
Linear Factor Graph where all factors are Gaussians.
Definition: Values.h:65
Definition: NonlinearFactorGraph.h:55
Definition: chartTesting.h:28
Definition: GaussianFactorGraph.h:73
3D rotation represented as a rotation matrix or quaternion