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>
24 #include <gtsam/inference/graph.h>
28 
29 #include <map>
30 #include <vector>
31 
32 namespace gtsam {
33 
34 typedef std::map<Key, std::vector<size_t> > KeyVectorMap;
35 typedef std::map<Key, Rot3> KeyRotMap;
36 
37 struct GTSAM_EXPORT InitializePose3 {
39  const NonlinearFactorGraph& g);
40 
41  static Values normalizeRelaxedRotations(const VectorValues& relaxedRot3);
42 
46  static Values computeOrientationsChordal(
47  const NonlinearFactorGraph& pose3Graph);
48 
52  static Values computeOrientationsGradient(
53  const NonlinearFactorGraph& pose3Graph, const Values& givenGuess,
54  size_t maxIter = 10000, const bool setRefFrame = true);
55 
56  static void createSymbolicGraph(const NonlinearFactorGraph& pose3Graph,
57  KeyVectorMap* adjEdgesMap,
58  KeyRotMap* factorId2RotMap);
59 
60  static Vector3 gradientTron(const Rot3& R1, const Rot3& R2, const double a,
61  const double b);
62 
67  static NonlinearFactorGraph buildPose3graph(
69 
73  static Values computePoses(const Values& initialRot,
74  NonlinearFactorGraph* poseGraph,
75  bool singleIter = true);
76 
82 
88  static Values initialize(const NonlinearFactorGraph& graph,
89  const Values& givenGuess, bool useGradient = false);
90 
92  static Values initialize(const NonlinearFactorGraph& graph);
93 };
94 } // end of namespace gtsam
Eigen::Vector3d Vector3
Definition: Vector.h:43
Factor Graph consisting of non-linear factors.
std::map< Key, Rot3 > KeyRotMap
NonlinearFactorGraph graph
static Values computePoses(const Values &initialRot, NonlinearFactorGraph *posegraph, bool singleIter=true)
void g(const string &key, int i)
Definition: testBTree.cpp:43
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
Definition: lago.cpp:161
Array33i a
std::map< Key, std::vector< size_t > > KeyVectorMap
Factor Graph Values.
Linear Factor Graph where all factors are Gaussians.
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:258
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
const G & b
Definition: Group.h:83
traits
Definition: chartTesting.h:28
Graph algorithm using boost library.
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:338
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
3D rotation represented as a rotation matrix or quaternion


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:14