#include <posest/pe3d.h>#include <frame_common/frame.h>#include <boost/shared_ptr.hpp>#include <cv.h>#include <cstdlib>#include <math.h>#include <posest/pe.h>#include <stdio.h>#include <iostream>#include <Eigen/Core>#include <Eigen/Geometry>#include "Core"#include "src/Core/util/DisableMSVCWarnings.h"#include "src/misc/Solve.h"#include "src/misc/Kernel.h"#include "src/misc/Image.h"#include "src/LU/FullPivLU.h"#include "src/LU/PartialPivLU.h"#include "src/LU/Determinant.h"#include "src/LU/Inverse.h"#include "src/Core/util/EnableMSVCWarnings.h"#include <Eigen/StdVector>#include <vector>#include <algorithm>#include "src/Cholesky/LLT.h"#include "src/Cholesky/LDLT.h"#include <Eigen/LU>#include <map>#include <sba/node.h>#include <stdlib.h>#include <limits.h>#include <bpcg/bpcg.h>#include <cstdio>

Go to the source code of this file.
Classes | |
| class | vslam::voSt |
| Stereo visual odometry class. Keeps track of a certain size window of latest frames in the system, estimates pose changes between frames, and optimizes the window using SBA. More... | |
Namespaces | |
| namespace | vslam |
Functions | |
| void | vslam::addPointCloudProjections (fc::Frame &f0, fc::Frame &f1, sba::SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w_frame0, const Matrix< double, 3, 4 > &f2w_frame1, int ndi0, int ndi1, std::vector< int > *ipts=NULL) |
| Adds point-plane projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts. | |
| void | vslam::addProjections (fc::Frame &f0, fc::Frame &f1, std::vector< fc::Frame, Eigen::aligned_allocator< fc::Frame > > &frames, sba::SysSBA &sba, const std::vector< cv::DMatch > &inliers, const Matrix< double, 3, 4 > &f2w, int ndi0, int ndi1, std::vector< int > *ipts=NULL) |
| Adds projections between two frames based on inlier matches. Adds any points not previously present in the external system, and fills in ipts. | |
| Vector3d | vslam::getProjection (fc::Frame &frame, int index) |
| Get a Vector3d projection from a keypoint at index. | |
| void | vslam::substPointRef (std::vector< int > &ipts, int tri0, int tri1) |
| substitutes tri0 for tri1 in a point reference vector. | |