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 kTypeLocalMap = 0,
00048 kTypeF2F = 1
00049 };
00050
00051 public:
00052 static Odometry * create(const ParametersMap & parameters);
00053 static Odometry * create(Type & type, const ParametersMap & parameters = ParametersMap());
00054
00055 public:
00056 virtual ~Odometry();
00057 Transform process(SensorData & data, OdometryInfo * info = 0);
00058 Transform process(SensorData & data, const Transform & guess, OdometryInfo * info = 0);
00059 virtual void reset(const Transform & initialPose = Transform::getIdentity());
00060
00061
00062 const Transform & getPose() const {return _pose;}
00063 bool isInfoDataFilled() const {return _fillInfoData;}
00064 const Transform & previousVelocityTransform() const {return previousVelocityTransform_;}
00065 double previousStamp() const {return previousStamp_;}
00066
00067 private:
00068 virtual Transform computeTransform(SensorData & data, const Transform & guess = Transform(), OdometryInfo * info = 0) = 0;
00069
00070 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);
00071 void predictKalmanFilter(float dt, float * vx=0, float * vy=0, float * vz=0, float * vroll=0, float * vpitch=0, float * vyaw=0);
00072 void updateKalmanFilter(float & vx, float & vy, float & vz, float & vroll, float & vpitch, float & vyaw);
00073
00074 private:
00075 int _resetCountdown;
00076 bool _force3DoF;
00077 bool _holonomic;
00078 bool guessFromMotion_;
00079 int _filteringStrategy;
00080 int _particleSize;
00081 float _particleNoiseT;
00082 float _particleLambdaT;
00083 float _particleNoiseR;
00084 float _particleLambdaR;
00085 bool _fillInfoData;
00086 float _kalmanProcessNoise;
00087 float _kalmanMeasurementNoise;
00088 int _imageDecimation;
00089 bool _alignWithGround;
00090 Transform _pose;
00091 int _resetCurrentCount;
00092 double previousStamp_;
00093 Transform previousVelocityTransform_;
00094 Transform previousGroundTruthPose_;
00095 float distanceTravelled_;
00096
00097 std::vector<ParticleFilter *> particleFilters_;
00098 cv::KalmanFilter kalmanFilter_;
00099
00100 protected:
00101 Odometry(const rtabmap::ParametersMap & parameters);
00102 };
00103
00104 }
00105 #endif