OdometryInfo.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 ODOMETRYINFO_H_
00029 #define ODOMETRYINFO_H_
00030 
00031 #include <map>
00032 #include "rtabmap/core/Transform.h"
00033 #include "rtabmap/core/RegistrationInfo.h"
00034 #include "rtabmap/core/CameraModel.h"
00035 #include "rtabmap/core/LaserScan.h"
00036 #include <opencv2/features2d/features2d.hpp>
00037 
00038 namespace rtabmap {
00039 
00040 class OdometryInfo
00041 {
00042 public:
00043         OdometryInfo() :
00044                 lost(true),
00045                 features(0),
00046                 localMapSize(0),
00047                 localScanMapSize(0),
00048                 localKeyFrames(0),
00049                 localBundleOutliers(0),
00050                 localBundleConstraints(0),
00051                 localBundleTime(0),
00052                 keyFrameAdded(false),
00053                 timeEstimation(0.0f),
00054                 timeParticleFiltering(0.0f),
00055                 stamp(0),
00056                 interval(0),
00057                 distanceTravelled(0.0f),
00058                 memoryUsage(0),
00059                 type(0)
00060         {}
00061 
00062         OdometryInfo copyWithoutData() const
00063         {
00064                 OdometryInfo output;
00065                 output.lost = lost;
00066                 output.reg = reg.copyWithoutData();
00067                 output.features = features;
00068                 output.localMapSize = localMapSize;
00069                 output.localScanMapSize = localScanMapSize;
00070                 output.localKeyFrames = localKeyFrames;
00071                 output.localBundleOutliers = localBundleOutliers;
00072                 output.localBundleConstraints = localBundleConstraints;
00073                 output.localBundleTime = localBundleTime;
00074                 output.localBundlePoses = localBundlePoses;
00075                 output.localBundleModels = localBundleModels;
00076                 output.keyFrameAdded = keyFrameAdded;
00077                 output.timeEstimation = timeEstimation;
00078                 output.timeParticleFiltering = timeParticleFiltering;
00079                 output.stamp = stamp;
00080                 output.interval = interval;
00081                 output.transform = transform;
00082                 output.transformFiltered = transformFiltered;
00083                 output.transformGroundTruth = transformGroundTruth;
00084                 output.distanceTravelled = distanceTravelled;
00085                 output.memoryUsage = memoryUsage;
00086                 output.type = type;
00087                 return output;
00088         }
00089 
00090         bool lost;
00091         RegistrationInfo reg;
00092         int features;
00093         int localMapSize;
00094         int localScanMapSize;
00095         int localKeyFrames;
00096         int localBundleOutliers;
00097         int localBundleConstraints;
00098         float localBundleTime;
00099         std::map<int, Transform> localBundlePoses;
00100         std::map<int, CameraModel> localBundleModels;
00101         bool keyFrameAdded;
00102         float timeEstimation;
00103         float timeParticleFiltering;
00104         double stamp;
00105         double interval;
00106         Transform transform;
00107         Transform transformFiltered;
00108         Transform transformGroundTruth;
00109         float distanceTravelled;
00110         int memoryUsage; //MB
00111 
00112         int type;
00113 
00114         // F2M
00115         std::multimap<int, cv::KeyPoint> words;
00116         std::map<int, cv::Point3f> localMap;
00117         LaserScan localScanMap;
00118 
00119         // F2F
00120         std::vector<cv::Point2f> refCorners;
00121         std::vector<cv::Point2f> newCorners;
00122         std::vector<int> cornerInliers;
00123 };
00124 
00125 }
00126 
00127 #endif /* ODOMETRYINFO_H_ */


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