|
class | AbstractHyperGraphElementCreator |
| Abstract interface for allocating HyperGraphElement. More...
|
|
class | AbstractOptimizationAlgorithmCreator |
| base for allocating an optimization algorithm More...
|
|
class | AbstractRobustKernelCreator |
| Abstract interface for allocating a robust kernel. More...
|
|
class | BaseBinaryEdge |
|
class | BaseEdge |
|
class | BaseMultiEdge |
| base class to represent an edge connecting an arbitrary number of nodes More...
|
|
class | BaseProperty |
|
class | BaseUnaryEdge |
|
class | BaseVertex |
| Templatized BaseVertex. More...
|
|
class | BlockSolver |
| Implementation of a solver operating on the blocks of the Hessian. More...
|
|
class | BlockSolverBase |
| base for the block solvers with some basic function interfaces More...
|
|
struct | BlockSolverTraits |
| traits to summarize the properties of the fixed size optimization problem More...
|
|
struct | BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > |
| traits to summarize the properties of the dynamic size optimization problem More...
|
|
class | Cache |
|
class | CacheContainer |
|
struct | ColSort |
|
class | DrawAction |
| draw actions More...
|
|
class | EdgeInverseSim3ProjectXYZ |
|
class | EdgeSE3ProjectXYZ |
|
class | EdgeSE3ProjectXYZOnlyPose |
|
class | EdgeSim3 |
| 7D edge between two Vertex7 More...
|
|
class | EdgeSim3ProjectXYZ |
|
class | EdgeStereoSE3ProjectXYZ |
|
class | EdgeStereoSE3ProjectXYZOnlyPose |
|
class | EstimatePropagator |
| propagation of an initial guess More...
|
|
class | EstimatePropagatorCost |
| cost for traversing along active edges in the optimizer More...
|
|
class | EstimatePropagatorCostOdometry |
| cost for traversing only odometry edges. More...
|
|
class | Factory |
| create vertices and edges based on TAGs in, for example, a file More...
|
|
struct | ForceLinker |
|
struct | G2OBatchStatistics |
| statistics about the optimization More...
|
|
struct | HyperDijkstra |
|
class | HyperGraph |
|
class | HyperGraphAction |
| Abstract action that operates on an entire graph. More...
|
|
class | HyperGraphActionLibrary |
| library of actions, indexed by the action name; More...
|
|
class | HyperGraphElementAction |
| Abstract action that operates on a graph entity. More...
|
|
class | HyperGraphElementActionCollection |
| collection of actions More...
|
|
class | HyperGraphElementCreator |
| templatized creator class which creates graph elements More...
|
|
class | JacobianWorkspace |
| provide memory workspace for computing the Jacobians More...
|
|
class | LinearSolver |
| basic solver for Ax = b More...
|
|
class | LinearSolverCCS |
| Solver with faster iterating structure for the linear matrix. More...
|
|
class | LinearSolverDense |
| linear solver using dense cholesky decomposition More...
|
|
class | LinearSolverEigen |
| linear solver which uses the sparse Cholesky solver from Eigen More...
|
|
class | MarginalCovarianceCholesky |
| computing the marginal covariance given a cholesky factor (lower triangle of the factor) More...
|
|
struct | MatrixElem |
|
class | MatrixStructure |
| representing the structure of a matrix in column compressed structure (only the upper triangular part of the matrix) More...
|
|
class | OpenMPMutex |
|
struct | OptimizableGraph |
|
class | OptimizationAlgorithm |
| Generic interface for a non-linear solver operating on a graph. More...
|
|
class | OptimizationAlgorithmDogleg |
| Implementation of Powell's Dogleg Algorithm. More...
|
|
class | OptimizationAlgorithmFactory |
| create solvers based on their short name More...
|
|
class | OptimizationAlgorithmGaussNewton |
| Implementation of the Gauss Newton Algorithm. More...
|
|
class | OptimizationAlgorithmLevenberg |
| Implementation of the Levenberg Algorithm. More...
|
|
struct | OptimizationAlgorithmProperty |
| describe the properties of a solver More...
|
|
class | OptimizationAlgorithmWithHessian |
| Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg. More...
|
|
class | Parameter |
|
class | ParameterContainer |
| map id to parameters More...
|
|
class | Property |
|
class | PropertyMap |
| a collection of properties mapping from name to the property itself More...
|
|
class | RegisterActionProxy |
|
class | RegisterOptimizationAlgorithmProxy |
|
class | RegisterRobustKernelProxy |
|
class | RegisterTypeProxy |
|
class | RobustKernel |
| base for all robust cost functions More...
|
|
class | RobustKernelCauchy |
| Cauchy cost function. More...
|
|
class | RobustKernelCreator |
| templatized creator class which creates graph elements More...
|
|
class | RobustKernelDCS |
| Dynamic covariance scaling - DCS. More...
|
|
class | RobustKernelFactory |
| create robust kernels based on their human readable name More...
|
|
class | RobustKernelHuber |
| Huber Cost Function. More...
|
|
class | RobustKernelPseudoHuber |
| Pseudo Huber Cost Function. More...
|
|
class | RobustKernelSaturated |
| Saturated cost function. More...
|
|
class | RobustKernelScaleDelta |
| scale a robust kernel to another delta (window size) More...
|
|
class | RobustKernelTukey |
| Tukey Cost Function. More...
|
|
class | ScopedOpenMPMutex |
| lock a mutex within a scope More...
|
|
class | ScopeTime |
| Class to measure the time spent in a scope. More...
|
|
class | SE3Quat |
|
struct | Sim3 |
|
class | Solver |
| Generic interface for a sparse solver operating on a graph which solves one iteration of the linearized objective function. More...
|
|
class | SparseBlockMatrix |
| Sparse matrix which uses blocks. More...
|
|
class | SparseBlockMatrixCCS |
| Sparse matrix which uses blocks. More...
|
|
class | SparseBlockMatrixDiagonal |
| Sparse matrix which uses blocks on the diagonal. More...
|
|
class | SparseBlockMatrixHashMap |
| Sparse matrix which uses blocks based on hash structures. More...
|
|
class | SparseOptimizer |
|
struct | UniformCostFunction |
|
class | VertexSBAPointXYZ |
| Point vertex, XYZ. More...
|
|
class | VertexSE3Expmap |
| SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential map. More...
|
|
class | VertexSim3Expmap |
| Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion. More...
|
|
class | WriteGnuplotAction |
|
|
typedef Eigen::Transform< double, 2, Eigen::Affine, Eigen::ColMajor > | Affine2D |
|
typedef Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > | Affine3D |
|
typedef std::vector< G2OBatchStatistics > | BatchStatisticsContainer |
|
typedef BlockSolver< BlockSolverTraits< 3, 2 > > | BlockSolver_3_2 |
|
typedef BlockSolver< BlockSolverTraits< 6, 3 > > | BlockSolver_6_3 |
|
typedef BlockSolver< BlockSolverTraits< 7, 3 > > | BlockSolver_7_3 |
|
typedef BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > | BlockSolverX |
|
typedef Property< bool > | BoolProperty |
|
typedef Property< double > | DoubleProperty |
|
typedef Property< float > | FloatProperty |
|
typedef void(* | ForceLinkFunction) (void) |
|
typedef Property< int > | IntProperty |
|
typedef Eigen::Transform< double, 2, Eigen::Isometry, Eigen::ColMajor > | Isometry2D |
|
typedef Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > | Isometry3D |
|
typedef Eigen::Matrix< double, 2, 2, Eigen::ColMajor > | Matrix2D |
|
typedef Eigen::Matrix< float, 2, 2, Eigen::ColMajor > | Matrix2F |
|
typedef Eigen::Matrix< int, 2, 2, Eigen::ColMajor > | Matrix2I |
|
typedef Eigen::Matrix< double, 3, 3, Eigen::ColMajor > | Matrix3D |
|
typedef Eigen::Matrix< float, 3, 3, Eigen::ColMajor > | Matrix3F |
|
typedef Eigen::Matrix< int, 3, 3, Eigen::ColMajor > | Matrix3I |
|
typedef Eigen::Matrix< double, 4, 4, Eigen::ColMajor > | Matrix4D |
|
typedef Eigen::Matrix< float, 4, 4, Eigen::ColMajor > | Matrix4F |
|
typedef Eigen::Matrix< int, 4, 4, Eigen::ColMajor > | Matrix4I |
|
typedef Matrix< double, 6, 6 > | Matrix6d |
|
typedef Matrix< double, 7, 7 > | Matrix7d |
|
typedef Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > | MatrixXD |
|
typedef Eigen::Matrix< float, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > | MatrixXF |
|
typedef Eigen::Matrix< int, Eigen::Dynamic, Eigen::Dynamic, Eigen::ColMajor > | MatrixXI |
|
typedef std::vector< Parameter * > | ParameterVector |
|
typedef std::tr1::shared_ptr< RobustKernel > | RobustKernelPtr |
|
typedef SparseBlockMatrix< MatrixXd > | SparseBlockMatrixXd |
|
typedef Property< std::string > | StringProperty |
|
typedef Eigen::Matrix< double, 2, 1, Eigen::ColMajor > | Vector2D |
|
typedef Eigen::Matrix< float, 2, 1, Eigen::ColMajor > | Vector2F |
|
typedef Eigen::Matrix< int, 2, 1, Eigen::ColMajor > | Vector2I |
|
typedef Eigen::Matrix< double, 3, 1, Eigen::ColMajor > | Vector3D |
|
typedef Eigen::Matrix< float, 3, 1, Eigen::ColMajor > | Vector3F |
|
typedef Eigen::Matrix< int, 3, 1, Eigen::ColMajor > | Vector3I |
|
typedef Eigen::Matrix< double, 4, 1, Eigen::ColMajor > | Vector4D |
|
typedef Eigen::Matrix< float, 4, 1, Eigen::ColMajor > | Vector4F |
|
typedef Eigen::Matrix< int, 4, 1, Eigen::ColMajor > | Vector4I |
|
typedef Matrix< double, 6, 1 > | Vector6d |
|
typedef Matrix< double, 7, 1 > | Vector7d |
|
typedef Eigen::Matrix< double, Eigen::Dynamic, 1, Eigen::ColMajor > | VectorXD |
|
typedef Eigen::Matrix< float, Eigen::Dynamic, 1, Eigen::ColMajor > | VectorXF |
|
typedef Eigen::Matrix< int, Eigen::Dynamic, 1, Eigen::ColMajor > | VectorXI |
|
|
void | applyAction (HyperGraph *graph, HyperGraphElementAction *action, HyperGraphElementAction::Parameters *params, const std::string &typeName) |
|
bool | arrayHasNaN (const double *array, int size, int *nanIndex=0) |
|
double | average_angle (double theta1, double theta2) |
|
template<typename T > |
T | clamp (T l, T x, T u) |
|
template<typename T > |
bool | convertString (const std::string &s, T &x, bool failIfLeftoverChars=true) |
|
double | deg2rad (double degree) |
|
Vector3d | deltaR (const Matrix3d &R) |
|
std::string | formatString (const char *fmt,...) |
|
double | get_monotonic_time () |
|
double | get_time () |
|
template<typename T > |
T | hypot (T x, T y) |
|
template<typename T > |
T | hypot_sqr (T x, T y) |
|
double | inverse_theta (double th) |
|
double | normalize_theta (double theta) |
|
bool | operator< (const HyperDijkstra::AdjacencyMapEntry &a, const HyperDijkstra::AdjacencyMapEntry &b) |
|
std::ostream & | operator<< (std::ostream &os, const G2OBatchStatistics &st) |
|
template<class MatrixType > |
std::ostream & | operator<< (std::ostream &, const SparseBlockMatrix< MatrixType > &m) |
|
std::ostream & | operator<< (std::ostream &out_str, const Sim3 &sim3) |
|
std::ostream & | operator<< (std::ostream &out_str, const SE3Quat &se3) |
|
Vector2d | project (const Vector3d &) |
|
Vector3d | project (const Vector4d &) |
|
Vector2d | project2d (const Vector3d &v) |
|
double | rad2deg (double rad) |
|
template<typename OutputIterator > |
OutputIterator | readFloats (const char *str, OutputIterator out) |
|
template<typename OutputIterator > |
OutputIterator | readInts (const char *str, OutputIterator out) |
|
int | readLine (std::istream &is, std::stringstream ¤tLine) |
|
template<typename T > |
int | sign (T x) |
|
Matrix3d | skew (const Vector3d &v) |
|
template<typename T > |
T | square (T x) |
|
bool | strEndsWith (const std::string &s, const std::string &end) |
|
std::string | strExpandFilename (const std::string &filename) |
|
template<typename T > |
T | stringToType (const std::string &s, bool failIfLeftoverChars=true) |
|
int | strPrintf (std::string &str, const char *fmt,...) |
|
std::vector< std::string > | strSplit (const std::string &str, const std::string &delimiters) |
|
bool | strStartsWith (const std::string &s, const std::string &start) |
|
std::string | strToLower (const std::string &s) |
|
std::string | strToUpper (const std::string &s) |
|
std::string | trim (const std::string &s) |
|
std::string | trimLeft (const std::string &s) |
|
std::string | trimRight (const std::string &s) |
|
Vector3d | unproject (const Vector2d &) |
|
Vector4d | unproject (const Vector3d &) |
|
Vector3d | unproject2d (const Vector2d &v) |
|
template<typename T > |
T | wrap (T l, T x, T u) |
|