LaserScan.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 CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_
00029 #define CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include <rtabmap/core/Transform.h>
00034 
00035 namespace rtabmap {
00036 
00037 class RTABMAP_EXP LaserScan
00038 {
00039 public:
00040         enum Format{kUnknown=0,
00041                 kXY=1,
00042                 kXYI=2,
00043                 kXYNormal=3,
00044                 kXYINormal=4,
00045                 kXYZ=5,
00046                 kXYZI=6,
00047                 kXYZRGB=7,
00048                 kXYZNormal=8,
00049                 kXYZINormal=9,
00050                 kXYZRGBNormal=10};
00051 
00052         static int channels(Format format);
00053         static bool isScan2d(const Format & format);
00054         static bool isScanHasNormals(const Format & format);
00055         static bool isScanHasRGB(const Format & format);
00056         static bool isScanHasIntensity(const Format & format);
00057         static LaserScan backwardCompatibility(const cv::Mat & oldScanFormat, int maxPoints = 0, int maxRange = 0, const Transform & localTransform = Transform::getIdentity());
00058 
00059 public:
00060         LaserScan();
00061         LaserScan(const cv::Mat & data, int maxPoints, float maxRange, Format format, const Transform & localTransform = Transform::getIdentity());
00062 
00063         const cv::Mat & data() const {return data_;}
00064         int maxPoints() const {return maxPoints_;}
00065         float maxRange() const {return maxRange_;}
00066         Format format() const {return format_;}
00067         Transform localTransform() const {return localTransform_;}
00068 
00069         bool isEmpty() const {return data_.empty();}
00070         int size() const {return data_.cols;}
00071         int dataType() const {return data_.type();}
00072         bool is2d() const {return isScan2d(format_);}
00073         bool hasNormals() const {return isScanHasNormals(format_);}
00074         bool hasRGB() const {return isScanHasRGB(format_);}
00075         bool hasIntensity() const {return isScanHasIntensity(format_);}
00076         bool isCompressed() const {return !data_.empty() && data_.type()==CV_8UC1;}
00077         LaserScan clone() const {return LaserScan(data_.clone(), maxPoints_, maxRange_, format_, localTransform_.clone());}
00078 
00079         int getIntensityOffset() const {return hasIntensity()?(is2d()?2:3):-1;}
00080         int getRGBOffset() const {return hasRGB()?(is2d()?2:3):-1;}
00081         int getNormalsOffset() const {return hasNormals()?(2 + (is2d()?0:1) + ((hasRGB() || hasIntensity())?1:0)):-1;}
00082 
00083         void clear() {data_ = cv::Mat();}
00084 
00085 private:
00086         cv::Mat data_;
00087         int maxPoints_;
00088         float maxRange_;
00089         Format format_;
00090         Transform localTransform_;
00091 };
00092 
00093 }
00094 
00095 #endif /* CORELIB_INCLUDE_RTABMAP_CORE_LASERSCAN_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:20