45 static Values computeOrientationsChordal(
51 static Values computeOrientationsGradient(
53 size_t maxIter = 10000,
const bool setRefFrame =
true);
56 KeyVectorMap* adjEdgesMap,
57 KeyRotMap* factorId2RotMap);
74 bool singleIter =
true);
88 const Values& givenGuess,
bool useGradient =
false);
Factor Graph consisting of non-linear factors.
std::map< Key, Rot3 > KeyRotMap
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Values computePoses(const Values &initialRot, NonlinearFactorGraph *posegraph, bool singleIter=true)
void g(const string &key, int i)
std::map< Key, std::vector< size_t > > KeyVectorMap
Linear Factor Graph where all factors are Gaussians.
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap &tree)
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
3D rotation represented as a rotation matrix or quaternion