#include <OdometryMono.h>
|
| enum | Type {
kTypeUndef = -1,
kTypeF2M = 0,
kTypeF2F = 1,
kTypeFovis = 2,
kTypeViso2 = 3,
kTypeDVO = 4,
kTypeORBSLAM = 5,
kTypeOkvis = 6,
kTypeLOAM = 7,
kTypeMSCKF = 8,
kTypeVINS = 9,
kTypeOpenVINS = 10,
kTypeFLOAM = 11,
kTypeOpen3D = 12
} |
| |
| static Odometry * | create (const ParametersMap ¶meters=ParametersMap()) |
| |
| static Odometry * | create (Type &type, const ParametersMap ¶meters=ParametersMap()) |
| |
| const std::map< double, Transform > & | imus () const |
| |
| | Odometry (const rtabmap::ParametersMap ¶meters) |
| |
Definition at line 39 of file OdometryMono.h.
◆ OdometryMono()
◆ ~OdometryMono()
| rtabmap::OdometryMono::~OdometryMono |
( |
| ) |
|
|
virtual |
◆ computeTransform()
◆ getType()
◆ reset()
| void rtabmap::OdometryMono::reset |
( |
const Transform & |
initialPose | ) |
|
|
virtual |
◆ feature2D_
◆ firstFrameGuessCorners_
| std::map<int, cv::Point2f> rtabmap::OdometryMono::firstFrameGuessCorners_ |
|
private |
◆ flowEps_
| double rtabmap::OdometryMono::flowEps_ |
|
private |
◆ flowIterations_
| int rtabmap::OdometryMono::flowIterations_ |
|
private |
◆ flowMaxLevel_
| int rtabmap::OdometryMono::flowMaxLevel_ |
|
private |
◆ flowWinSize_
| int rtabmap::OdometryMono::flowWinSize_ |
|
private |
◆ fundMatrixConfidence_
| float rtabmap::OdometryMono::fundMatrixConfidence_ |
|
private |
◆ fundMatrixReprojError_
| float rtabmap::OdometryMono::fundMatrixReprojError_ |
|
private |
◆ initMinFlow_
| float rtabmap::OdometryMono::initMinFlow_ |
|
private |
◆ initMinTranslation_
| float rtabmap::OdometryMono::initMinTranslation_ |
|
private |
◆ iterations_
| int rtabmap::OdometryMono::iterations_ |
|
private |
◆ keyFrameLinks_
| std::multimap<int, Link> rtabmap::OdometryMono::keyFrameLinks_ |
|
private |
◆ keyFrameModels_
| std::map<int, std::vector<CameraModel> > rtabmap::OdometryMono::keyFrameModels_ |
|
private |
◆ keyFramePoses_
| std::map<int, Transform> rtabmap::OdometryMono::keyFramePoses_ |
|
private |
◆ keyFrameThr_
| float rtabmap::OdometryMono::keyFrameThr_ |
|
private |
◆ keyFrameWords3D_
| std::map<int, std::map<int, cv::Point3f> > rtabmap::OdometryMono::keyFrameWords3D_ |
|
private |
◆ localHistoryMaxSize_
| int rtabmap::OdometryMono::localHistoryMaxSize_ |
|
private |
◆ localMap_
| std::map<int, cv::Point3f> rtabmap::OdometryMono::localMap_ |
|
private |
◆ maxVariance_
| float rtabmap::OdometryMono::maxVariance_ |
|
private |
◆ memory_
| Memory* rtabmap::OdometryMono::memory_ |
|
private |
◆ minInliers_
| int rtabmap::OdometryMono::minInliers_ |
|
private |
◆ minTranslation_
| float rtabmap::OdometryMono::minTranslation_ |
|
private |
◆ pnpFlags_
| int rtabmap::OdometryMono::pnpFlags_ |
|
private |
◆ pnpRefineIterations_
| int rtabmap::OdometryMono::pnpRefineIterations_ |
|
private |
◆ pnpReprojError_
| double rtabmap::OdometryMono::pnpReprojError_ |
|
private |
The documentation for this class was generated from the following files: