46 static Values computeOrientationsChordal(
52 static Values computeOrientationsGradient(
54 size_t maxIter = 10000,
const bool setRefFrame =
true);
57 KeyVectorMap* adjEdgesMap,
58 KeyRotMap* factorId2RotMap);
75 bool singleIter =
true);
89 const Values& givenGuess,
bool useGradient =
false);
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)
GaussianFactorGraph buildLinearOrientationGraph(const vector< size_t > &spanningTreeIds, const vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
std::map< Key, std::vector< size_t > > KeyVectorMap
Linear Factor Graph where all factors are Gaussians.
VectorValues initializeOrientations(const NonlinearFactorGraph &graph, bool useOdometricPath)
Q R1(Eigen::AngleAxisd(1, Q_z_axis))
Graph algorithm using boost library.
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Q R2(Eigen::AngleAxisd(2, Vector3(0, 1, 0)))
3D rotation represented as a rotation matrix or quaternion