SensorData.cpp
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 
00029 #include "rtabmap/core/SensorData.h"
00030 #include "rtabmap/core/Compression.h"
00031 #include "rtabmap/utilite/ULogger.h"
00032 #include <rtabmap/utilite/UMath.h>
00033 
00034 namespace rtabmap
00035 {
00036 
00037 // empty constructor
00038 SensorData::SensorData() :
00039                 _id(0),
00040                 _stamp(0.0),
00041                 _laserScanMaxPts(0),
00042                 _laserScanMaxRange(0.0f)
00043 {
00044 }
00045 
00046 // Appearance-only constructor
00047 SensorData::SensorData(
00048                 const cv::Mat & image,
00049                 int id,
00050                 double stamp,
00051                 const cv::Mat & userData) :
00052                 _id(id),
00053                 _stamp(stamp),
00054                 _laserScanMaxPts(0),
00055                 _laserScanMaxRange(0.0f)
00056 {
00057         if(image.rows == 1)
00058         {
00059                 UASSERT(image.type() == CV_8UC1); // Bytes
00060                 _imageCompressed = image;
00061         }
00062         else if(!image.empty())
00063         {
00064                 UASSERT(image.type() == CV_8UC1 || // Mono
00065                                 image.type() == CV_8UC3);  // RGB
00066                 _imageRaw = image;
00067         }
00068 
00069         if(userData.type() == CV_8UC1) // Bytes
00070         {
00071                 _userDataCompressed = userData; // assume compressed
00072         }
00073         else
00074         {
00075                 _userDataRaw = userData;
00076         }
00077 }
00078 
00079 // Mono constructor
00080 SensorData::SensorData(
00081                 const cv::Mat & image,
00082                 const CameraModel & cameraModel,
00083                 int id,
00084                 double stamp,
00085                 const cv::Mat & userData) :
00086                 _id(id),
00087                 _stamp(stamp),
00088                 _laserScanMaxPts(0),
00089                 _laserScanMaxRange(0.0f),
00090                 _cameraModels(std::vector<CameraModel>(1, cameraModel))
00091 {
00092         if(image.rows == 1)
00093         {
00094                 UASSERT(image.type() == CV_8UC1); // Bytes
00095                 _imageCompressed = image;
00096         }
00097         else if(!image.empty())
00098         {
00099                 UASSERT(image.type() == CV_8UC1 || // Mono
00100                                 image.type() == CV_8UC3);  // RGB
00101                 _imageRaw = image;
00102         }
00103 
00104         if(userData.type() == CV_8UC1) // Bytes
00105         {
00106                 _userDataCompressed = userData; // assume compressed
00107         }
00108         else
00109         {
00110                 _userDataRaw = userData;
00111         }
00112 }
00113 
00114 // RGB-D constructor
00115 SensorData::SensorData(
00116                 const cv::Mat & rgb,
00117                 const cv::Mat & depth,
00118                 const CameraModel & cameraModel,
00119                 int id,
00120                 double stamp,
00121                 const cv::Mat & userData) :
00122                 _id(id),
00123                 _stamp(stamp),
00124                 _laserScanMaxPts(0),
00125                 _laserScanMaxRange(0.0f),
00126                 _cameraModels(std::vector<CameraModel>(1, cameraModel))
00127 {
00128         if(rgb.rows == 1)
00129         {
00130                 UASSERT(rgb.type() == CV_8UC1); // Bytes
00131                 _imageCompressed = rgb;
00132         }
00133         else if(!rgb.empty())
00134         {
00135                 UASSERT(rgb.type() == CV_8UC1 || // Mono
00136                                 rgb.type() == CV_8UC3);  // RGB
00137                 _imageRaw = rgb;
00138         }
00139 
00140         if(depth.rows == 1)
00141         {
00142                 UASSERT(depth.type() == CV_8UC1); // Bytes
00143                 _depthOrRightCompressed = depth;
00144         }
00145         else if(!depth.empty())
00146         {
00147                 UASSERT(depth.type() == CV_32FC1 || // Depth in meter
00148                                 depth.type() == CV_16UC1); // Depth in millimetre
00149                 _depthOrRightRaw = depth;
00150         }
00151 
00152         if(userData.type() == CV_8UC1) // Bytes
00153         {
00154                 _userDataCompressed = userData; // assume compressed
00155         }
00156         else
00157         {
00158                 _userDataRaw = userData;
00159         }
00160 }
00161 
00162 // RGB-D constructor + laser scan
00163 SensorData::SensorData(
00164                 const cv::Mat & laserScan,
00165                 int laserScanMaxPts,
00166                 float laserScanMaxRange,
00167                 const cv::Mat & rgb,
00168                 const cv::Mat & depth,
00169                 const CameraModel & cameraModel,
00170                 int id,
00171                 double stamp,
00172                 const cv::Mat & userData) :
00173                 _id(id),
00174                 _stamp(stamp),
00175                 _laserScanMaxPts(laserScanMaxPts),
00176                 _laserScanMaxRange(laserScanMaxRange),
00177                 _cameraModels(std::vector<CameraModel>(1, cameraModel))
00178 {
00179         if(rgb.rows == 1)
00180         {
00181                 UASSERT(rgb.type() == CV_8UC1); // Bytes
00182                 _imageCompressed = rgb;
00183         }
00184         else if(!rgb.empty())
00185         {
00186                 UASSERT(rgb.type() == CV_8UC1 || // Mono
00187                                 rgb.type() == CV_8UC3);  // RGB
00188                 _imageRaw = rgb;
00189         }
00190         if(depth.rows == 1)
00191         {
00192                 UASSERT(depth.type() == CV_8UC1); // Bytes
00193                 _depthOrRightCompressed = depth;
00194         }
00195         else if(!depth.empty())
00196         {
00197                 UASSERT(depth.type() == CV_32FC1 || // Depth in meter
00198                                 depth.type() == CV_16UC1); // Depth in millimetre
00199                 _depthOrRightRaw = depth;
00200         }
00201 
00202         if(laserScan.type() == CV_32FC2 || laserScan.type() == CV_32FC3 || laserScan.type() == CV_32FC(6))
00203         {
00204                 _laserScanRaw = laserScan;
00205         }
00206         else if(!laserScan.empty())
00207         {
00208                 UASSERT(laserScan.type() == CV_8UC1); // Bytes
00209                 _laserScanCompressed = laserScan;
00210         }
00211 
00212         if(userData.type() == CV_8UC1) // Bytes
00213         {
00214                 _userDataCompressed = userData; // assume compressed
00215         }
00216         else
00217         {
00218                 _userDataRaw = userData;
00219         }
00220 }
00221 
00222 // Multi-cameras RGB-D constructor
00223 SensorData::SensorData(
00224                 const cv::Mat & rgb,
00225                 const cv::Mat & depth,
00226                 const std::vector<CameraModel> & cameraModels,
00227                 int id,
00228                 double stamp,
00229                 const cv::Mat & userData) :
00230                 _id(id),
00231                 _stamp(stamp),
00232                 _laserScanMaxPts(0),
00233                 _laserScanMaxRange(0.0f),
00234                 _cameraModels(cameraModels)
00235 {
00236         if(rgb.rows == 1)
00237         {
00238                 UASSERT(rgb.type() == CV_8UC1); // Bytes
00239                 _imageCompressed = rgb;
00240         }
00241         else if(!rgb.empty())
00242         {
00243                 UASSERT(rgb.type() == CV_8UC1 || // Mono
00244                                 rgb.type() == CV_8UC3);  // RGB
00245                 _imageRaw = rgb;
00246         }
00247         if(depth.rows == 1)
00248         {
00249                 UASSERT(depth.type() == CV_8UC1); // Bytes
00250                 _depthOrRightCompressed = depth;
00251         }
00252         else if(!depth.empty())
00253         {
00254                 UASSERT(depth.type() == CV_32FC1 || // Depth in meter
00255                                 depth.type() == CV_16UC1); // Depth in millimetre
00256                 _depthOrRightRaw = depth;
00257         }
00258 
00259         if(userData.type() == CV_8UC1) // Bytes
00260         {
00261                 _userDataCompressed = userData; // assume compressed
00262         }
00263         else
00264         {
00265                 _userDataRaw = userData;
00266         }
00267 }
00268 
00269 // Multi-cameras RGB-D constructor + laser scan
00270 SensorData::SensorData(
00271                 const cv::Mat & laserScan,
00272                 int laserScanMaxPts,
00273                 float laserScanMaxRange,
00274                 const cv::Mat & rgb,
00275                 const cv::Mat & depth,
00276                 const std::vector<CameraModel> & cameraModels,
00277                 int id,
00278                 double stamp,
00279                 const cv::Mat & userData) :
00280                 _id(id),
00281                 _stamp(stamp),
00282                 _laserScanMaxPts(laserScanMaxPts),
00283                 _laserScanMaxRange(laserScanMaxRange),
00284                 _cameraModels(cameraModels)
00285 {
00286         if(rgb.rows == 1)
00287         {
00288                 UASSERT(rgb.type() == CV_8UC1); // Bytes
00289                 _imageCompressed = rgb;
00290         }
00291         else if(!rgb.empty())
00292         {
00293                 UASSERT(rgb.type() == CV_8UC1 || // Mono
00294                                 rgb.type() == CV_8UC3);  // RGB
00295                 _imageRaw = rgb;
00296         }
00297         if(depth.rows == 1)
00298         {
00299                 UASSERT(depth.type() == CV_8UC1); // Bytes
00300                 _depthOrRightCompressed = depth;
00301         }
00302         else if(!depth.empty())
00303         {
00304                 UASSERT(depth.type() == CV_32FC1 || // Depth in meter
00305                                 depth.type() == CV_16UC1); // Depth in millimetre
00306                 _depthOrRightRaw = depth;
00307         }
00308 
00309         if(laserScan.type() == CV_32FC2 || laserScan.type() == CV_32FC3 || laserScan.type() == CV_32FC(6))
00310         {
00311                 _laserScanRaw = laserScan;
00312         }
00313         else if(!laserScan.empty())
00314         {
00315                 UASSERT(laserScan.type() == CV_8UC1); // Bytes
00316                 _laserScanCompressed = laserScan;
00317         }
00318 
00319         if(userData.type() == CV_8UC1) // Bytes
00320         {
00321                 _userDataCompressed = userData; // assume compressed
00322         }
00323         else
00324         {
00325                 _userDataRaw = userData;
00326         }
00327 }
00328 
00329 // Stereo constructor
00330 SensorData::SensorData(
00331                 const cv::Mat & left,
00332                 const cv::Mat & right,
00333                 const StereoCameraModel & cameraModel,
00334                 int id,
00335                 double stamp,
00336                 const cv::Mat & userData):
00337                 _id(id),
00338                 _stamp(stamp),
00339                 _laserScanMaxPts(0),
00340                 _laserScanMaxRange(0.0f),
00341                 _stereoCameraModel(cameraModel)
00342 {
00343         if(left.rows == 1)
00344         {
00345                 UASSERT(left.type() == CV_8UC1); // Bytes
00346                 _imageCompressed = left;
00347         }
00348         else if(!left.empty())
00349         {
00350                 UASSERT(left.type() == CV_8UC1 || // Mono
00351                                 left.type() == CV_8UC3 || // RGB
00352                                 left.type() == CV_16UC1); // IR
00353                 _imageRaw = left;
00354         }
00355         if(right.rows == 1)
00356         {
00357                 UASSERT(right.type() == CV_8UC1); // Bytes
00358                 _depthOrRightCompressed = right;
00359         }
00360         else if(!right.empty())
00361         {
00362                 UASSERT(right.type() == CV_8UC1 || // Mono
00363                                 right.type() == CV_16UC1);  // IR
00364                 _depthOrRightRaw = right;
00365         }
00366 
00367         if(userData.type() == CV_8UC1) // Bytes
00368         {
00369                 _userDataCompressed = userData; // assume compressed
00370         }
00371         else
00372         {
00373                 _userDataRaw = userData;
00374         }
00375 
00376 }
00377 
00378 // Stereo constructor + 2d laser scan
00379 SensorData::SensorData(
00380                 const cv::Mat & laserScan,
00381                 int laserScanMaxPts,
00382                 float laserScanMaxRange,
00383                 const cv::Mat & left,
00384                 const cv::Mat & right,
00385                 const StereoCameraModel & cameraModel,
00386                 int id,
00387                 double stamp,
00388                 const cv::Mat & userData) :
00389                 _id(id),
00390                 _stamp(stamp),
00391                 _laserScanMaxPts(laserScanMaxPts),
00392                 _laserScanMaxRange(laserScanMaxRange),
00393                 _stereoCameraModel(cameraModel)
00394 {
00395         if(left.rows == 1)
00396         {
00397                 UASSERT(left.type() == CV_8UC1); // Bytes
00398                 _imageCompressed = left;
00399         }
00400         else if(!left.empty())
00401         {
00402                 UASSERT(left.type() == CV_8UC1 || // Mono
00403                                 left.type() == CV_8UC3);  // RGB
00404                 _imageRaw = left;
00405         }
00406         if(right.rows == 1)
00407         {
00408                 UASSERT(right.type() == CV_8UC1); // Bytes
00409                 _depthOrRightCompressed = right;
00410         }
00411         else if(!right.empty())
00412         {
00413                 UASSERT(right.type() == CV_8UC1); // Mono
00414                 _depthOrRightRaw = right;
00415         }
00416 
00417         if(laserScan.type() == CV_32FC2 || laserScan.type() == CV_32FC3 || laserScan.type() == CV_32FC(6))
00418         {
00419                 _laserScanRaw = laserScan;
00420         }
00421         else if(!laserScan.empty())
00422         {
00423                 UASSERT(laserScan.type() == CV_8UC1); // Bytes
00424                 _laserScanCompressed = laserScan;
00425         }
00426 
00427         if(userData.type() == CV_8UC1) // Bytes
00428         {
00429                 _userDataCompressed = userData; // assume compressed
00430         }
00431         else
00432         {
00433                 _userDataRaw = userData;
00434         }
00435 }
00436 
00437 void SensorData::setUserDataRaw(const cv::Mat & userDataRaw)
00438 {
00439         if(!userDataRaw.empty() && (!_userDataCompressed.empty() || !_userDataRaw.empty()))
00440         {
00441                 UWARN("Cannot write new user data (%d bytes) over existing user "
00442                           "data (%d bytes, %d compressed). Set user data of %d to null "
00443                           "before setting a new one.",
00444                           int(userDataRaw.total()*userDataRaw.elemSize()),
00445                           int(_userDataRaw.total()*_userDataRaw.elemSize()),
00446                           _userDataCompressed.cols,
00447                           this->id());
00448                 return;
00449         }
00450         _userDataRaw = userDataRaw;
00451 }
00452 
00453 void SensorData::setUserData(const cv::Mat & userData)
00454 {
00455         if(!userData.empty() && (!_userDataCompressed.empty() || !_userDataRaw.empty()))
00456         {
00457                 UWARN("Cannot write new user data (%d bytes) over existing user "
00458                           "data (%d bytes, %d compressed). Set user data of %d to null "
00459                           "before setting a new one.",
00460                           int(userData.total()*userData.elemSize()),
00461                           int(_userDataRaw.total()*_userDataRaw.elemSize()),
00462                           _userDataCompressed.cols,
00463                           this->id());
00464                 return;
00465         }
00466         _userDataRaw = cv::Mat();
00467         _userDataCompressed = cv::Mat();
00468 
00469         if(!userData.empty())
00470         {
00471                 if(userData.type() == CV_8UC1) // Bytes
00472                 {
00473                         _userDataCompressed = userData; // assume compressed
00474                 }
00475                 else
00476                 {
00477                         _userDataRaw = userData;
00478                         _userDataCompressed = compressData2(userData);
00479                 }
00480         }
00481 }
00482 
00483 void SensorData::uncompressData()
00484 {
00485         cv::Mat tmpA, tmpB, tmpC, tmpD;
00486         uncompressData(_imageCompressed.empty()?0:&tmpA,
00487                                 _depthOrRightCompressed.empty()?0:&tmpB,
00488                                 _laserScanCompressed.empty()?0:&tmpC,
00489                                 _userDataCompressed.empty()?0:&tmpD);
00490 }
00491 
00492 void SensorData::uncompressData(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw, cv::Mat * userDataRaw)
00493 {
00494         uncompressDataConst(imageRaw, depthRaw, laserScanRaw, userDataRaw);
00495         if(imageRaw && !imageRaw->empty() && _imageRaw.empty())
00496         {
00497                 _imageRaw = *imageRaw;
00498                 //backward compatibility, set image size in camera model if not set
00499                 if(!_imageRaw.empty() && _cameraModels.size())
00500                 {
00501                         cv::Size size(_imageRaw.cols/_cameraModels.size(), _imageRaw.rows/_cameraModels.size());
00502                         for(unsigned int i=0; i<_cameraModels.size(); ++i)
00503                         {
00504                                 if(_cameraModels[i].isValidForProjection() && _cameraModels[i].imageWidth() == 0)
00505                                 {
00506                                         _cameraModels[i].setImageSize(size);
00507                                 }
00508                         }
00509                 }
00510         }
00511         if(depthRaw && !depthRaw->empty() && _depthOrRightRaw.empty())
00512         {
00513                 _depthOrRightRaw = *depthRaw;
00514         }
00515         if(laserScanRaw && !laserScanRaw->empty() && _laserScanRaw.empty())
00516         {
00517                 _laserScanRaw = *laserScanRaw;
00518         }
00519         if(userDataRaw && !userDataRaw->empty() && _userDataRaw.empty())
00520         {
00521                 _userDataRaw = *userDataRaw;
00522         }
00523 }
00524 
00525 void SensorData::uncompressDataConst(cv::Mat * imageRaw, cv::Mat * depthRaw, cv::Mat * laserScanRaw, cv::Mat * userDataRaw) const
00526 {
00527         if(imageRaw)
00528         {
00529                 *imageRaw = _imageRaw;
00530         }
00531         if(depthRaw)
00532         {
00533                 *depthRaw = _depthOrRightRaw;
00534         }
00535         if(laserScanRaw)
00536         {
00537                 *laserScanRaw = _laserScanRaw;
00538         }
00539         if(userDataRaw)
00540         {
00541                 *userDataRaw = _userDataRaw;
00542         }
00543         if( (imageRaw && imageRaw->empty()) ||
00544                 (depthRaw && depthRaw->empty()) ||
00545                 (laserScanRaw && laserScanRaw->empty()) ||
00546                 (userDataRaw && userDataRaw->empty()))
00547         {
00548                 rtabmap::CompressionThread ctImage(_imageCompressed, true);
00549                 rtabmap::CompressionThread ctDepth(_depthOrRightCompressed, true);
00550                 rtabmap::CompressionThread ctLaserScan(_laserScanCompressed, false);
00551                 rtabmap::CompressionThread ctUserData(_userDataCompressed, false);
00552                 if(imageRaw && imageRaw->empty())
00553                 {
00554                         ctImage.start();
00555                 }
00556                 if(depthRaw && depthRaw->empty())
00557                 {
00558                         ctDepth.start();
00559                 }
00560                 if(laserScanRaw && laserScanRaw->empty())
00561                 {
00562                         ctLaserScan.start();
00563                 }
00564                 if(userDataRaw && userDataRaw->empty())
00565                 {
00566                         ctUserData.start();
00567                 }
00568                 ctImage.join();
00569                 ctDepth.join();
00570                 ctLaserScan.join();
00571                 ctUserData.join();
00572                 if(imageRaw && imageRaw->empty())
00573                 {
00574                         *imageRaw = ctImage.getUncompressedData();
00575                         if(imageRaw->empty())
00576                         {
00577                                 UWARN("Requested raw image data, but the sensor data (%d) doesn't have image.", this->id());
00578                         }
00579                 }
00580                 if(depthRaw && depthRaw->empty())
00581                 {
00582                         *depthRaw = ctDepth.getUncompressedData();
00583                         if(depthRaw->empty())
00584                         {
00585                                 UWARN("Requested depth/right image data, but the sensor data (%d) doesn't have depth/right image.", this->id());
00586                         }
00587                 }
00588                 if(laserScanRaw && laserScanRaw->empty())
00589                 {
00590                         *laserScanRaw = ctLaserScan.getUncompressedData();
00591 
00592                         if(laserScanRaw->empty())
00593                         {
00594                                 UWARN("Requested laser scan data, but the sensor data (%d) doesn't have laser scan.", this->id());
00595                         }
00596                 }
00597                 if(userDataRaw && userDataRaw->empty())
00598                 {
00599                         *userDataRaw = ctUserData.getUncompressedData();
00600 
00601                         if(userDataRaw->empty())
00602                         {
00603                                 UWARN("Requested user data, but the sensor data (%d) doesn't have user data.", this->id());
00604                         }
00605                 }
00606         }
00607 }
00608 
00609 long SensorData::getMemoryUsed() const // Return memory usage in Bytes
00610 {
00611         return _imageCompressed.total()*_imageCompressed.elemSize() +
00612                         _imageRaw.total()*_imageRaw.elemSize() +
00613                         _depthOrRightCompressed.total()*_depthOrRightCompressed.elemSize() +
00614                         _depthOrRightRaw.total()*_depthOrRightRaw.elemSize() +
00615                         _userDataCompressed.total()*_userDataCompressed.elemSize() +
00616                         _userDataRaw.total()*_userDataRaw.elemSize() +
00617                         _laserScanCompressed.total()*_laserScanCompressed.elemSize() +
00618                         _laserScanRaw.total()*_laserScanRaw.elemSize();
00619 }
00620 
00621 } // namespace rtabmap
00622 


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