#include <sys/time.h>
#include <visualization_msgs/Marker.h>
#include <geometry_msgs/Point.h>
#include "graph_manager.h"
#include "misc.h"
#include <opencv2/features2d/features2d.hpp>
#include <QThread>
#include <qtconcurrentrun.h>
#include <QtConcurrentMap>
#include <utility>
#include <fstream>
#include <limits>
#include <boost/foreach.hpp>
#include <pcl_ros/point_cloud.h>
#include "g2o/types/slam3d/se3quat.h"
#include "g2o/types/slam3d/edge_se3.h"
#include "g2o/core/block_solver.h"
#include "g2o/core/optimizable_graph.h"
#include "g2o/solvers/csparse/linear_solver_csparse.h"
#include "g2o/solvers/cholmod/linear_solver_cholmod.h"
#include "g2o/solvers/pcg/linear_solver_pcg.h"
#include "g2o/solvers/dense/linear_solver_dense.h"
#include "g2o/core/sparse_optimizer.h"
#include "g2o/core/optimization_algorithm_dogleg.h"
#include "g2o/core/optimization_algorithm_levenberg.h"
#include "scoped_timer.h"
Go to the source code of this file.
Typedefs | |
typedef std::set < g2o::HyperGraph::Edge * > | EdgeSet |
typedef g2o::BlockSolver < g2o::BlockSolverTraits< 6, 3 > > | SlamBlockSolver |
typedef g2o::LinearSolverCholmod < SlamBlockSolver::PoseMatrixType > | SlamLinearCholmodSolver |
typedef g2o::LinearSolverCSparse < SlamBlockSolver::PoseMatrixType > | SlamLinearCSparseSolver |
typedef g2o::LinearSolverDense < SlamBlockSolver::PoseMatrixType > | SlamLinearDenseSolver |
typedef g2o::LinearSolverPCG < SlamBlockSolver::PoseMatrixType > | SlamLinearPCGSolver |
typedef std::tr1::unordered_map< int, g2o::HyperGraph::Vertex * > | VertexIDMap |
typedef std::pair< int, g2o::HyperGraph::Vertex * > | VertexIDPair |
Functions | |
bool | containsVertex (g2o::HyperGraph::Edge *myedge, g2o::HyperGraph::Vertex *v_to_del) |
void | fixationOfVertices (std::string strategy, g2o::SparseOptimizer *optimizer, std::map< int, Node * > &graph, g2o::HyperGraph::VertexSet &camera_vertices, int earliest_loop_closure_node) |
void | updateInlierFeatures (const MatchingResult &mr, Node *new_node, Node *old_node) |
Definition at line 60 of file graph_manager.cpp.
typedef g2o::BlockSolver< g2o::BlockSolverTraits<6, 3> > SlamBlockSolver |
Definition at line 51 of file graph_manager.cpp.
typedef g2o::LinearSolverCholmod<SlamBlockSolver::PoseMatrixType> SlamLinearCholmodSolver |
Definition at line 53 of file graph_manager.cpp.
typedef g2o::LinearSolverCSparse<SlamBlockSolver::PoseMatrixType> SlamLinearCSparseSolver |
Definition at line 52 of file graph_manager.cpp.
typedef g2o::LinearSolverDense<SlamBlockSolver::PoseMatrixType> SlamLinearDenseSolver |
Definition at line 55 of file graph_manager.cpp.
typedef g2o::LinearSolverPCG<SlamBlockSolver::PoseMatrixType> SlamLinearPCGSolver |
Definition at line 54 of file graph_manager.cpp.
typedef std::tr1::unordered_map<int, g2o::HyperGraph::Vertex*> VertexIDMap |
Definition at line 57 of file graph_manager.cpp.
typedef std::pair<int, g2o::HyperGraph::Vertex*> VertexIDPair |
Definition at line 58 of file graph_manager.cpp.
bool containsVertex | ( | g2o::HyperGraph::Edge * | myedge, |
g2o::HyperGraph::Vertex * | v_to_del | ||
) |
Definition at line 1068 of file graph_manager.cpp.
void fixationOfVertices | ( | std::string | strategy, |
g2o::SparseOptimizer * | optimizer, | ||
std::map< int, Node * > & | graph, | ||
g2o::HyperGraph::VertexSet & | camera_vertices, | ||
int | earliest_loop_closure_node | ||
) |
Definition at line 911 of file graph_manager.cpp.
void updateInlierFeatures | ( | const MatchingResult & | mr, |
Node * | new_node, | ||
Node * | old_node | ||
) |
Definition at line 409 of file graph_manager.cpp.