Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ODOMETRY_H_
00029 #define ODOMETRY_H_
00030
00031 #include <rtabmap/core/RtabmapExp.h>
00032
00033 #include <rtabmap/core/Transform.h>
00034 #include <rtabmap/core/SensorData.h>
00035 #include <rtabmap/core/Parameters.h>
00036
00037 namespace rtabmap {
00038
00039 class OdometryInfo;
00040 class ParticleFilter;
00041
00042 class RTABMAP_EXP Odometry
00043 {
00044 public:
00045 enum Type {
00046 kTypeUndef = -1,
00047 kTypeF2M = 0,
00048 kTypeF2F = 1,
00049 kTypeFovis = 2,
00050 kTypeViso2 = 3,
00051 kTypeDVO = 4,
00052 kTypeORBSLAM2 = 5,
00053 kTypeOkvis = 6,
00054 kTypeLOAM = 7,
00055 kTypeMSCKF = 8
00056 };
00057
00058 public:
00059 static Odometry * create(const ParametersMap & parameters);
00060 static Odometry * create(Type & type, const ParametersMap & parameters = ParametersMap());
00061
00062 public:
00063 virtual ~Odometry();
00064 Transform process(SensorData & data, OdometryInfo * info = 0);
00065 Transform process(SensorData & data, const Transform & guess, OdometryInfo * info = 0);
00066 virtual void reset(const Transform & initialPose = Transform::getIdentity());
00067 virtual Odometry::Type getType() = 0;
00068 virtual bool canProcessRawImages() const {return false;}
00069
00070
00071 const Transform & getPose() const {return _pose;}
00072 bool isInfoDataFilled() const {return _fillInfoData;}
00073 const Transform & previousVelocityTransform() const {return previousVelocityTransform_;}
00074 double previousStamp() const {return previousStamp_;}
00075 unsigned int framesProcessed() const {return framesProcessed_;}
00076 bool imagesAlreadyRectified() const {return _imagesAlreadyRectified;}
00077
00078 private:
00079 virtual Transform computeTransform(SensorData & data, const Transform & guess = Transform(), OdometryInfo * info = 0) = 0;
00080
00081 void initKalmanFilter(const Transform & initialPose = Transform::getIdentity(), float vx=0.0f, float vy=0.0f, float vz=0.0f, float vroll=0.0f, float vpitch=0.0f, float vyaw=0.0f);
00082 void predictKalmanFilter(float dt, float * vx=0, float * vy=0, float * vz=0, float * vroll=0, float * vpitch=0, float * vyaw=0);
00083 void updateKalmanFilter(float & vx, float & vy, float & vz, float & vroll, float & vpitch, float & vyaw);
00084
00085 private:
00086 int _resetCountdown;
00087 bool _force3DoF;
00088 bool _holonomic;
00089 bool guessFromMotion_;
00090 int _filteringStrategy;
00091 int _particleSize;
00092 float _particleNoiseT;
00093 float _particleLambdaT;
00094 float _particleNoiseR;
00095 float _particleLambdaR;
00096 bool _fillInfoData;
00097 float _kalmanProcessNoise;
00098 float _kalmanMeasurementNoise;
00099 int _imageDecimation;
00100 bool _alignWithGround;
00101 bool _publishRAMUsage;
00102 bool _imagesAlreadyRectified;
00103 Transform _pose;
00104 int _resetCurrentCount;
00105 double previousStamp_;
00106 Transform previousVelocityTransform_;
00107 Transform previousGroundTruthPose_;
00108 float distanceTravelled_;
00109 unsigned int framesProcessed_;
00110
00111 std::vector<ParticleFilter *> particleFilters_;
00112 cv::KalmanFilter kalmanFilter_;
00113
00114 protected:
00115 Odometry(const rtabmap::ParametersMap & parameters);
00116 };
00117
00118 }
00119 #endif