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 DBREADER_H_
00029 #define DBREADER_H_
00030
00031 #include "rtabmap/core/RtabmapExp.h"
00032
00033 #include <rtabmap/utilite/UTimer.h>
00034 #include <rtabmap/core/Transform.h>
00035 #include <rtabmap/core/Camera.h>
00036
00037 #include <opencv2/core/core.hpp>
00038
00039 #include <set>
00040 #include <list>
00041
00042 namespace rtabmap {
00043
00044 class DBDriver;
00045
00046 class RTABMAP_EXP DBReader : public Camera {
00047 public:
00048 DBReader(const std::string & databasePath,
00049 float frameRate = 0.0f,
00050 bool odometryIgnored = false,
00051 bool ignoreGoalDelay = false,
00052 bool goalsIgnored = false,
00053 int startIndex = 0,
00054 int cameraIndex = -1);
00055 DBReader(const std::list<std::string> & databasePaths,
00056 float frameRate = 0.0f,
00057 bool odometryIgnored = false,
00058 bool ignoreGoalDelay = false,
00059 bool goalsIgnored = false,
00060 int startIndex = 0,
00061 int cameraIndex = -1);
00062 virtual ~DBReader();
00063
00064 virtual bool init(
00065 const std::string & calibrationFolder = ".",
00066 const std::string & cameraName = "");
00067
00068 virtual bool isCalibrated() const;
00069 virtual std::string getSerial() const;
00070 virtual bool odomProvided() const {return !_odometryIgnored;}
00071
00072 protected:
00073 virtual SensorData captureImage(CameraInfo * info = 0);
00074
00075 private:
00076 SensorData getNextData(CameraInfo * info = 0);
00077
00078 private:
00079 std::list<std::string> _paths;
00080 bool _odometryIgnored;
00081 bool _ignoreGoalDelay;
00082 bool _goalsIgnored;
00083 int _startIndex;
00084 int _cameraIndex;
00085
00086 DBDriver * _dbDriver;
00087 UTimer _timer;
00088 std::set<int> _ids;
00089 std::set<int>::iterator _currentId;
00090 double _previousStamp;
00091 int _previousMapID;
00092 bool _calibrated;
00093 };
00094
00095 }
00096 #endif