SensorData.cpp
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 
00029 #include "rtabmap/core/SensorData.h"
00030 #include "rtabmap/utilite/ULogger.h"
00031 #include <rtabmap/utilite/UMath.h>
00032 
00033 namespace rtabmap
00034 {
00035 
00039 SensorData::SensorData() :
00040         _id(0),
00041         _stamp(0.0),
00042         _fx(0.0f),
00043         _fyOrBaseline(0.0f),
00044         _cx(0.0f),
00045         _cy(0.0f),
00046         _localTransform(Transform::getIdentity()),
00047         _poseRotVariance(1.0f),
00048         _poseTransVariance(1.0f),
00049         _laserScanMaxPts(0)
00050 {
00051 }
00052 
00053 SensorData::SensorData(const cv::Mat & image,
00054           int id,
00055           double stamp,
00056           const std::vector<unsigned char> & userData) :
00057         _image(image),
00058         _id(id),
00059         _stamp(stamp),
00060         _fx(0.0f),
00061         _fyOrBaseline(0.0f),
00062         _cx(0.0f),
00063         _cy(0.0f),
00064         _localTransform(Transform::getIdentity()),
00065         _poseRotVariance(1.0f),
00066         _poseTransVariance(1.0f),
00067         _laserScanMaxPts(0),
00068         _userData(userData)
00069 {
00070         UASSERT(image.empty() ||
00071                         image.type() == CV_8UC1 || // Mono
00072                         image.type() == CV_8UC3);  // RGB
00073 }
00074 
00075         // Metric constructor
00076 SensorData::SensorData(const cv::Mat & image,
00077                   const cv::Mat & depthOrRightImage,
00078                   float fx,
00079                   float fyOrBaseline,
00080                   float cx,
00081                   float cy,
00082                   const Transform & localTransform,
00083                   const Transform & pose,
00084                   float poseRotVariance,
00085                   float poseTransVariance,
00086                   int id,
00087                   double stamp,
00088                   const std::vector<unsigned char> & userData) :
00089         _image(image),
00090         _id(id),
00091         _stamp(stamp),
00092         _depthOrRightImage(depthOrRightImage),
00093         _fx(fx),
00094         _fyOrBaseline(fyOrBaseline),
00095         _cx(cx),
00096         _cy(cy),
00097         _pose(pose),
00098         _localTransform(localTransform),
00099         _poseRotVariance(poseRotVariance),
00100         _poseTransVariance(poseTransVariance),
00101         _laserScanMaxPts(0),
00102         _userData(userData)
00103 {
00104         UASSERT(image.empty() ||
00105                         image.type() == CV_8UC1 || // Mono
00106                         image.type() == CV_8UC3);  // RGB
00107         UASSERT(depthOrRightImage.empty() ||
00108                         depthOrRightImage.type() == CV_32FC1 || // Depth in meter
00109                         depthOrRightImage.type() == CV_16UC1 || // Depth in millimetre
00110                         depthOrRightImage.type() == CV_8U);     // Right stereo image
00111         UASSERT(!_localTransform.isNull());
00112         UASSERT_MSG(uIsFinite(_poseRotVariance) && _poseRotVariance>0 && uIsFinite(_poseTransVariance) && _poseTransVariance>0, "Rotational and transitional variances should not be null! (set to 1 if unknown)");
00113 }
00114 
00115         // Metric constructor + 2d depth
00116 SensorData::SensorData(const cv::Mat & laserScan,
00117                   int laserScanMaxPts,
00118                   const cv::Mat & image,
00119                   const cv::Mat & depthOrRightImage,
00120                   float fx,
00121                   float fyOrBaseline,
00122                   float cx,
00123                   float cy,
00124                   const Transform & localTransform,
00125                   const Transform & pose,
00126                   float poseRotVariance,
00127                   float poseTransVariance,
00128                   int id,
00129                   double stamp,
00130                   const std::vector<unsigned char> & userData) :
00131         _image(image),
00132         _id(id),
00133         _stamp(stamp),
00134         _depthOrRightImage(depthOrRightImage),
00135         _laserScan(laserScan),
00136         _fx(fx),
00137         _fyOrBaseline(fyOrBaseline),
00138         _cx(cx),
00139         _cy(cy),
00140         _pose(pose),
00141         _localTransform(localTransform),
00142         _poseRotVariance(poseRotVariance),
00143         _poseTransVariance(poseTransVariance),
00144         _laserScanMaxPts(laserScanMaxPts),
00145         _userData(userData)
00146 {
00147         UASSERT(_laserScan.empty() || _laserScan.type() == CV_32FC2);
00148         UASSERT(image.empty() ||
00149                         image.type() == CV_8UC1 || // Mono
00150                         image.type() == CV_8UC3);  // RGB
00151         UASSERT(depthOrRightImage.empty() ||
00152                         depthOrRightImage.type() == CV_32FC1 || // Depth in meter
00153                         depthOrRightImage.type() == CV_16UC1 || // Depth in millimetre
00154                         depthOrRightImage.type() == CV_8U);     // Right stereo image
00155         UASSERT(!_localTransform.isNull());
00156         UASSERT_MSG(uIsFinite(_poseRotVariance) && _poseRotVariance>0 && uIsFinite(_poseTransVariance) && _poseTransVariance>0, "Rotational and transitional variances should not be null! (set to 1 if unknown)");
00157 }
00158 
00159 bool SensorData::empty() const
00160 {
00161         return _image.empty();
00162 }
00163 
00164 } // namespace rtabmap
00165 


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