Namespaces | Typedefs | Functions
lago.h File Reference

Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers: More...

#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/linear/GaussianFactorGraph.h>
#include <gtsam/linear/VectorValues.h>
#include <gtsam/inference/graph.h>
Include dependency graph for lago.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 gtsam
 traits
 
 gtsam::lago
 

Typedefs

typedef std::map< Key, double > gtsam::lago::key2doubleMap
 

Functions

GTSAM_EXPORT GaussianFactorGraph gtsam::lago::buildLinearOrientationGraph (const std::vector< size_t > &spanningTreeIds, const std::vector< size_t > &chordsIds, const NonlinearFactorGraph &g, const key2doubleMap &orientationsToRoot, const PredecessorMap< Key > &tree)
 
key2doubleMap gtsam::lago::computeThetasToRoot (const key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree)
 
GTSAM_EXPORT void gtsam::lago::getSymbolicGraph (std::vector< size_t > &spanningTreeIds, std::vector< size_t > &chordsIds, key2doubleMap &deltaThetaMap, const PredecessorMap< Key > &tree, const NonlinearFactorGraph &g)
 
Values gtsam::lago::initialize (const NonlinearFactorGraph &graph, bool useOdometricPath)
 
Values gtsam::lago::initialize (const NonlinearFactorGraph &graph, const Values &initialGuess)
 
VectorValues gtsam::lago::initializeOrientations (const NonlinearFactorGraph &graph, bool useOdometricPath)
 

Detailed Description

Initialize Pose2 in a factor graph using LAGO (Linear Approximation for Graph Optimization). see papers:

Author
Luca Carlone
Frank Dellaert
Date
May 14, 2014

L. Carlone, R. Aragues, J. Castellanos, and B. Bona, A fast and accurate approximation for planar pose graph optimization, IJRR, 2014.

L. Carlone, R. Aragues, J.A. Castellanos, and B. Bona, A linear approximation for graph-based simultaneous localization and mapping, RSS, 2011.

Parameters
graphnonlinear factor graph (can include arbitrary factors but we assume that there is a subgraph involving Pose2 and betweenFactors). Also in the current version we assume that there is an odometric spanning path (x0->x1, x1->x2, etc) and a prior on x0. This assumption can be relaxed by using the extra argument useOdometricPath = false, although this part of code is not stable yet.
Returns
Values: initial guess from LAGO (only pose2 are initialized)
Author
Luca Carlone
Frank Dellaert
Date
May 14, 2014

Definition in file lago.h.



gtsam
Author(s):
autogenerated on Sat May 8 2021 02:51:30