SensorData.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, 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 SENSORDATA_H_
00029 #define SENSORDATA_H_
00030 
00031 #include <rtabmap/core/RtabmapExp.h>
00032 #include <rtabmap/core/Transform.h>
00033 #include <rtabmap/core/CameraModel.h>
00034 #include <rtabmap/core/StereoCameraModel.h>
00035 #include <rtabmap/core/Transform.h>
00036 #include <opencv2/core/core.hpp>
00037 #include <opencv2/features2d/features2d.hpp>
00038 
00039 namespace rtabmap
00040 {
00041 
00045 class RTABMAP_EXP SensorData
00046 {
00047 public:
00048         // empty constructor
00049         SensorData();
00050 
00051         // Appearance-only constructor
00052         SensorData(
00053                         const cv::Mat & image,
00054                         int id = 0,
00055                         double stamp = 0.0,
00056                         const cv::Mat & userData = cv::Mat());
00057 
00058         // Mono constructor
00059         SensorData(
00060                         const cv::Mat & image,
00061                         const CameraModel & cameraModel,
00062                         int id = 0,
00063                         double stamp = 0.0,
00064                         const cv::Mat & userData = cv::Mat());
00065 
00066         // RGB-D constructor
00067         SensorData(
00068                         const cv::Mat & rgb,
00069                         const cv::Mat & depth,
00070                         const CameraModel & cameraModel,
00071                         int id = 0,
00072                         double stamp = 0.0,
00073                         const cv::Mat & userData = cv::Mat());
00074 
00075         // RGB-D constructor + laser scan
00076         SensorData(
00077                         const cv::Mat & laserScan,
00078                         int laserScanMaxPts,
00079                         float laserScanMaxRange,
00080                         const cv::Mat & rgb,
00081                         const cv::Mat & depth,
00082                         const CameraModel & cameraModel,
00083                         int id = 0,
00084                         double stamp = 0.0,
00085                         const cv::Mat & userData = cv::Mat());
00086 
00087         // Multi-cameras RGB-D constructor
00088         SensorData(
00089                         const cv::Mat & rgb,
00090                         const cv::Mat & depth,
00091                         const std::vector<CameraModel> & cameraModels,
00092                         int id = 0,
00093                         double stamp = 0.0,
00094                         const cv::Mat & userData = cv::Mat());
00095 
00096         // Multi-cameras RGB-D constructor + laser scan
00097         SensorData(
00098                         const cv::Mat & laserScan,
00099                         int laserScanMaxPts,
00100                         float laserScanMaxRange,
00101                         const cv::Mat & rgb,
00102                         const cv::Mat & depth,
00103                         const std::vector<CameraModel> & cameraModels,
00104                         int id = 0,
00105                         double stamp = 0.0,
00106                         const cv::Mat & userData = cv::Mat());
00107 
00108         // Stereo constructor
00109         SensorData(
00110                         const cv::Mat & left,
00111                         const cv::Mat & right,
00112                         const StereoCameraModel & cameraModel,
00113                         int id = 0,
00114                         double stamp = 0.0,
00115                         const cv::Mat & userData = cv::Mat());
00116 
00117         // Stereo constructor + laser scan
00118         SensorData(
00119                         const cv::Mat & laserScan,
00120                         int laserScanMaxPts,
00121                         float laserScanMaxRange,
00122                         const cv::Mat & left,
00123                         const cv::Mat & right,
00124                         const StereoCameraModel & cameraModel,
00125                         int id = 0,
00126                         double stamp = 0.0,
00127                         const cv::Mat & userData = cv::Mat());
00128 
00129         virtual ~SensorData() {}
00130 
00131         bool isValid() const {
00132                 return !(_id == 0 &&
00133                         _stamp == 0.0 &&
00134                         _laserScanMaxPts == 0 &&
00135                         _imageRaw.empty() &&
00136                         _imageCompressed.empty() &&
00137                         _depthOrRightRaw.empty() &&
00138                         _depthOrRightCompressed.empty() &&
00139                         _laserScanRaw.empty() &&
00140                         _laserScanCompressed.empty() &&
00141                         _cameraModels.size() == 0 &&
00142                         !_stereoCameraModel.isValidForProjection() &&
00143                         _userDataRaw.empty() &&
00144                         _userDataCompressed.empty() &&
00145                         _keypoints.size() == 0 &&
00146                         _descriptors.empty());
00147         }
00148 
00149         int id() const {return _id;}
00150         void setId(int id) {_id = id;}
00151         double stamp() const {return _stamp;}
00152         void setStamp(double stamp) {_stamp = stamp;}
00153         int laserScanMaxPts() const {return _laserScanMaxPts;}
00154         float laserScanMaxRange() const {return _laserScanMaxRange;}
00155 
00156         const cv::Mat & imageCompressed() const {return _imageCompressed;}
00157         const cv::Mat & depthOrRightCompressed() const {return _depthOrRightCompressed;}
00158         const cv::Mat & laserScanCompressed() const {return _laserScanCompressed;}
00159 
00160         const cv::Mat & imageRaw() const {return _imageRaw;}
00161         const cv::Mat & depthOrRightRaw() const {return _depthOrRightRaw;}
00162         const cv::Mat & laserScanRaw() const {return _laserScanRaw;}
00163         void setImageRaw(const cv::Mat & imageRaw) {_imageRaw = imageRaw;}
00164         void setDepthOrRightRaw(const cv::Mat & depthOrImageRaw) {_depthOrRightRaw =depthOrImageRaw;}
00165         void setLaserScanRaw(const cv::Mat & laserScanRaw, int maxPts, float maxRange) {_laserScanRaw =laserScanRaw;_laserScanMaxPts = maxPts;_laserScanMaxRange=maxRange;}
00166         void setCameraModel(const CameraModel & model) {_cameraModels.clear(); _cameraModels.push_back(model);}
00167         void setCameraModels(const std::vector<CameraModel> & models) {_cameraModels = models;}
00168         void setStereoCameraModel(const StereoCameraModel & stereoCameraModel) {_stereoCameraModel = stereoCameraModel;}
00169 
00170         //for convenience
00171         cv::Mat depthRaw() const {return _depthOrRightRaw.type()!=CV_8UC1?_depthOrRightRaw:cv::Mat();}
00172         cv::Mat rightRaw() const {return _depthOrRightRaw.type()==CV_8UC1?_depthOrRightRaw:cv::Mat();}
00173 
00174         void uncompressData();
00175         void uncompressData(cv::Mat * imageRaw, cv::Mat * depthOrRightRaw, cv::Mat * laserScanRaw = 0, cv::Mat * userDataRaw = 0);
00176         void uncompressDataConst(cv::Mat * imageRaw, cv::Mat * depthOrRightRaw, cv::Mat * laserScanRaw = 0, cv::Mat * userDataRaw = 0) const;
00177 
00178         const std::vector<CameraModel> & cameraModels() const {return _cameraModels;}
00179         const StereoCameraModel & stereoCameraModel() const {return _stereoCameraModel;}
00180 
00181         void setUserDataRaw(const cv::Mat & userDataRaw); // only set raw
00182         void setUserData(const cv::Mat & userData); // detect automatically if raw or compressed. If raw, the data is compressed too.
00183         const cv::Mat & userDataRaw() const {return _userDataRaw;}
00184         const cv::Mat & userDataCompressed() const {return _userDataCompressed;}
00185 
00186         void setFeatures(const std::vector<cv::KeyPoint> & keypoints, const cv::Mat & descriptors)
00187         {
00188                 _keypoints = keypoints;
00189                 _descriptors = descriptors;
00190         }
00191         const std::vector<cv::KeyPoint> & keypoints() const {return _keypoints;}
00192         const cv::Mat & descriptors() const {return _descriptors;}
00193 
00194         void setGroundTruth(const Transform & pose) {groundTruth_ = pose;}
00195         const Transform & groundTruth() const {return groundTruth_;}
00196 
00197         long getMemoryUsed() const; // Return memory usage in Bytes
00198 
00199 private:
00200         int _id;
00201         double _stamp;
00202         int _laserScanMaxPts;
00203         float _laserScanMaxRange;
00204 
00205         cv::Mat _imageCompressed;          // compressed image
00206         cv::Mat _depthOrRightCompressed;   // compressed image
00207         cv::Mat _laserScanCompressed;      // compressed data
00208 
00209         cv::Mat _imageRaw;          // CV_8UC1 or CV_8UC3
00210         cv::Mat _depthOrRightRaw;   // depth CV_16UC1 or CV_32FC1, right image CV_8UC1
00211         cv::Mat _laserScanRaw;      // CV_32FC2 or CV_32FC3
00212 
00213         std::vector<CameraModel> _cameraModels;
00214         StereoCameraModel _stereoCameraModel;
00215 
00216         // user data
00217         cv::Mat _userDataCompressed;      // compressed data
00218         cv::Mat _userDataRaw;
00219 
00220         // features
00221         std::vector<cv::KeyPoint> _keypoints;
00222         cv::Mat _descriptors;
00223 
00224         Transform groundTruth_;
00225 };
00226 
00227 }
00228 
00229 
00230 #endif /* SENSORDATA_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17