#include <OdometryF2M.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 44 of file OdometryF2M.h.
◆ OdometryF2M()
◆ ~OdometryF2M()
rtabmap::OdometryF2M::~OdometryF2M |
( |
| ) |
|
|
virtual |
◆ computeTransform()
◆ getLastFrame()
const Signature& rtabmap::OdometryF2M::getLastFrame |
( |
| ) |
const |
|
inline |
◆ getMap()
const Signature& rtabmap::OdometryF2M::getMap |
( |
| ) |
const |
|
inline |
◆ getType()
◆ reset()
◆ bundleAdjustment_
int rtabmap::OdometryF2M::bundleAdjustment_ |
|
private |
◆ bundleIMUOrientations_
std::multimap<int, Link> rtabmap::OdometryF2M::bundleIMUOrientations_ |
|
private |
◆ bundleLinks_
std::multimap<int, Link> rtabmap::OdometryF2M::bundleLinks_ |
|
private |
◆ bundleMaxFrames_
int rtabmap::OdometryF2M::bundleMaxFrames_ |
|
private |
◆ bundleModels_
std::map<int, std::vector<CameraModel> > rtabmap::OdometryF2M::bundleModels_ |
|
private |
◆ bundlePoseReferences_
std::map<int, int> rtabmap::OdometryF2M::bundlePoseReferences_ |
|
private |
◆ bundlePoses_
◆ bundleSeq_
int rtabmap::OdometryF2M::bundleSeq_ |
|
private |
◆ bundleWordReferences_
std::map<int, std::map<int, FeatureBA> > rtabmap::OdometryF2M::bundleWordReferences_ |
|
private |
◆ keyFrameThr_
float rtabmap::OdometryF2M::keyFrameThr_ |
|
private |
◆ lastFrame_
◆ lastFrameOldestNewId_
int rtabmap::OdometryF2M::lastFrameOldestNewId_ |
|
private |
◆ map_
◆ maximumMapSize_
int rtabmap::OdometryF2M::maximumMapSize_ |
|
private |
◆ maxNewFeatures_
int rtabmap::OdometryF2M::maxNewFeatures_ |
|
private |
◆ parameters_
◆ pointToPlaneK_
int rtabmap::OdometryF2M::pointToPlaneK_ |
|
private |
◆ pointToPlaneRadius_
float rtabmap::OdometryF2M::pointToPlaneRadius_ |
|
private |
◆ regPipeline_
◆ sba_
◆ scanKeyFrameThr_
float rtabmap::OdometryF2M::scanKeyFrameThr_ |
|
private |
◆ scanMapMaxRange_
float rtabmap::OdometryF2M::scanMapMaxRange_ |
|
private |
◆ scanMaximumMapSize_
int rtabmap::OdometryF2M::scanMaximumMapSize_ |
|
private |
◆ scansBuffer_
std::vector<std::pair<pcl::PointCloud<pcl::PointXYZINormal>::Ptr, pcl::IndicesPtr> > rtabmap::OdometryF2M::scansBuffer_ |
|
private |
◆ scanSubtractAngle_
float rtabmap::OdometryF2M::scanSubtractAngle_ |
|
private |
◆ scanSubtractRadius_
float rtabmap::OdometryF2M::scanSubtractRadius_ |
|
private |
◆ validDepthRatio_
float rtabmap::OdometryF2M::validDepthRatio_ |
|
private |
◆ visKeyFrameThr_
int rtabmap::OdometryF2M::visKeyFrameThr_ |
|
private |
The documentation for this class was generated from the following files: