GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Static Public Member Functions | List of all members
gtsam::InitializePose3 Struct Reference

Static Public Member Functions

static GaussianFactorGraph buildLinearOrientationGraph (const NonlinearFactorGraph &g)
 
static Values normalizeRelaxedRotations (const VectorValues &relaxedRot3)
 
static Values computeOrientationsChordal (const NonlinearFactorGraph &pose3Graph)
 
static Values computeOrientationsGradient (const NonlinearFactorGraph &pose3Graph, const Values &givenGuess, size_t maxIter=10000, const bool setRefFrame=true)
 
static void createSymbolicGraph (const NonlinearFactorGraph &pose3Graph, KeyVectorMap *adjEdgesMap, KeyRotMap *factorId2RotMap)
 
static Vector3 gradientTron (const Rot3 &R1, const Rot3 &R2, const double a, const double b)
 
static NonlinearFactorGraph buildPose3graph (const NonlinearFactorGraph &graph)
 
static Values computePoses (const Values &initialRot, NonlinearFactorGraph *poseGraph, bool singleIter=true)
 
static Values initializeOrientations (const NonlinearFactorGraph &graph)
 
static Values initialize (const NonlinearFactorGraph &graph, const Values &givenGuess, bool useGradient=false)
 
static Values initialize (const NonlinearFactorGraph &graph)
 Calls initialize above using Chordal method.
 

Member Function Documentation

◆ buildPose3graph()

static NonlinearFactorGraph gtsam::InitializePose3::buildPose3graph ( const NonlinearFactorGraph graph)
static

Select the subgraph of betweenFactors and transforms priors into between wrt a fictitious node

◆ computeOrientationsChordal()

static Values gtsam::InitializePose3::computeOrientationsChordal ( const NonlinearFactorGraph pose3Graph)
static

Return the orientations of a graph including only BetweenFactors<Pose3>

◆ computeOrientationsGradient()

static Values gtsam::InitializePose3::computeOrientationsGradient ( const NonlinearFactorGraph pose3Graph,
const Values givenGuess,
size_t  maxIter = 10000,
const bool  setRefFrame = true 
)
static

Return the orientations of a graph including only BetweenFactors<Pose3>

◆ computePoses()

static Values gtsam::InitializePose3::computePoses ( const Values initialRot,
NonlinearFactorGraph poseGraph,
bool  singleIter = true 
)
static

Use Gauss-Newton optimizer to optimize for poses given rotation estimates

◆ initialize()

static Values gtsam::InitializePose3::initialize ( const NonlinearFactorGraph graph,
const Values givenGuess,
bool  useGradient = false 
)
static

"extract" the Pose3 subgraph of the original graph, get orientations from relative orientation measurements (using either gradient or chordal method), and finish up with 1 GN iteration on full poses.

◆ initializeOrientations()

static Values gtsam::InitializePose3::initializeOrientations ( const NonlinearFactorGraph graph)
static

"extract" the Pose3 subgraph of the original graph, get orientations from relative orientation measurements using chordal method.


The documentation for this struct was generated from the following file: