Odometry.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 #include <pcl/point_types.h>
00037 #include <pcl/point_cloud.h>
00038 
00039 class UTimer;
00040 
00041 namespace rtabmap {
00042 
00043 class Feature2D;
00044 class OdometryInfo;
00045 
00046 class RTABMAP_EXP Odometry
00047 {
00048 public:
00049         virtual ~Odometry() {}
00050         Transform process(const SensorData & data, OdometryInfo * info = 0);
00051         virtual void reset(const Transform & initialPose = Transform::getIdentity());
00052 
00053         //getters
00054         const Transform & getPose() const {return _pose;}
00055         const std::string & getRoiRatios() const {return _roiRatios;}
00056         int getMinInliers() const {return _minInliers;}
00057         float getInlierDistance() const {return _inlierDistance;}
00058         int getIterations() const {return _iterations;}
00059         int getRefineIterations() const {return _refineIterations;}
00060         float getMaxDepth() const {return _maxDepth;}
00061         bool isInfoDataFilled() const {return _fillInfoData;}
00062         bool isPnPEstimationUsed() const {return _pnpEstimation;}
00063         double getPnPReprojError() const {return _pnpReprojError;}
00064         int  getPnPFlags() const {return _pnpFlags;}
00065 
00066 private:
00067         virtual Transform computeTransform(const SensorData & image, OdometryInfo * info = 0) = 0;
00068 
00069 private:
00070         std::string _roiRatios;
00071         int _minInliers;
00072         float _inlierDistance;
00073         int _iterations;
00074         int _refineIterations;
00075         float _maxDepth;
00076         int _resetCountdown;
00077         bool _force2D;
00078         bool _fillInfoData;
00079         bool _pnpEstimation;
00080         double _pnpReprojError;
00081         int _pnpFlags;
00082         Transform _pose;
00083         int _resetCurrentCount;
00084 
00085 protected:
00086         Odometry(const rtabmap::ParametersMap & parameters);
00087 };
00088 
00089 class Memory;
00090 
00091 class RTABMAP_EXP OdometryBOW : public Odometry
00092 {
00093 public:
00094         OdometryBOW(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
00095         virtual ~OdometryBOW();
00096 
00097         virtual void reset(const Transform & initialPose = Transform::getIdentity());
00098         const std::multimap<int, pcl::PointXYZ> & getLocalMap() const {return localMap_;}
00099         const Memory * getMemory() const {return _memory;}
00100 
00101 private:
00102         virtual Transform computeTransform(const SensorData & image, OdometryInfo * info = 0);
00103 
00104 private:
00105         //Parameters
00106         int _localHistoryMaxSize;
00107 
00108         Memory * _memory;
00109         std::multimap<int, pcl::PointXYZ> localMap_;
00110 };
00111 
00112 class RTABMAP_EXP OdometryOpticalFlow : public Odometry
00113 {
00114 public:
00115         OdometryOpticalFlow(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
00116         virtual ~OdometryOpticalFlow();
00117 
00118         virtual void reset(const Transform & initialPose = Transform::getIdentity());
00119 
00120         const cv::Mat & getLastFrame() const {return refFrame_;}
00121         const std::vector<cv::Point2f> & getLastCorners() const {return refCorners_;}
00122         const pcl::PointCloud<pcl::PointXYZ>::Ptr & getLastCorners3D() const {return refCorners3D_;}
00123 
00124 private:
00125         virtual Transform computeTransform(const SensorData & image, OdometryInfo * info = 0);
00126         Transform computeTransformStereo(const SensorData & image, OdometryInfo * info);
00127         Transform computeTransformRGBD(const SensorData & image, OdometryInfo * info);
00128         Transform computeTransformMono(const SensorData & image, OdometryInfo * info);
00129 private:
00130         //Parameters:
00131         int flowWinSize_;
00132         int flowIterations_;
00133         double flowEps_;
00134         int flowMaxLevel_;
00135 
00136         int stereoWinSize_;
00137         int stereoIterations_;
00138         double stereoEps_;
00139         int stereoMaxLevel_;
00140         float stereoMaxSlope_;
00141 
00142         int subPixWinSize_;
00143         int subPixIterations_;
00144         double subPixEps_;
00145 
00146         Feature2D * feature2D_;
00147 
00148         cv::Mat refFrame_;
00149         cv::Mat refRightFrame_;
00150         std::vector<cv::Point2f> refCorners_;
00151         pcl::PointCloud<pcl::PointXYZ>::Ptr refCorners3D_;
00152 };
00153 
00154 class RTABMAP_EXP OdometryMono : public Odometry
00155 {
00156 public:
00157         OdometryMono(const rtabmap::ParametersMap & parameters = rtabmap::ParametersMap());
00158         virtual ~OdometryMono();
00159         virtual void reset(const Transform & initialPose);
00160 
00161 private:
00162         virtual Transform computeTransform(const SensorData & data, OdometryInfo * info = 0);
00163 private:
00164         //Parameters:
00165         int flowWinSize_;
00166         int flowIterations_;
00167         double flowEps_;
00168         int flowMaxLevel_;
00169 
00170         Memory * memory_;
00171         int localHistoryMaxSize_;
00172         float initMinFlow_;
00173         float initMinTranslation_;
00174         float minTranslation_;
00175         float fundMatrixReprojError_;
00176         float fundMatrixConfidence_;
00177 
00178         cv::Mat refDepth_;
00179         std::map<int, cv::Point2f> cornersMap_;
00180         std::multimap<int, cv::Point3f> localMap_;
00181         std::map<int, std::multimap<int, pcl::PointXYZ> > keyFrameWords3D_;
00182         std::map<int, Transform> keyFramePoses_;
00183         float maxVariance_;
00184 };
00185 
00186 class RTABMAP_EXP OdometryICP : public Odometry
00187 {
00188 public:
00189         OdometryICP(int decimation = 4,
00190                         float voxelSize = 0.005f,
00191                         int samples = 0,
00192                         float maxCorrespondenceDistance = 0.05f,
00193                         int maxIterations = 30,
00194                         float correspondenceRatio = 0.7f,
00195                         bool pointToPlane = true,
00196                         const ParametersMap & odometryParameter = rtabmap::ParametersMap());
00197         virtual void reset(const Transform & initialPose = Transform::getIdentity());
00198 
00199 private:
00200         virtual Transform computeTransform(const SensorData & image, OdometryInfo * info = 0);
00201 
00202 private:
00203         int _decimation;
00204         float _voxelSize;
00205         float _samples;
00206         float _maxCorrespondenceDistance;
00207         int     _maxIterations;
00208         float _correspondenceRatio;
00209         bool _pointToPlane;
00210 
00211         pcl::PointCloud<pcl::PointNormal>::Ptr _previousCloudNormal; // for point ot plane
00212         pcl::PointCloud<pcl::PointXYZ>::Ptr _previousCloud; // for point to point
00213 };
00214 
00215 } /* namespace rtabmap */
00216 #endif /* ODOMETRY_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:32