Link.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 #include "rtabmap/core/Link.h"
00029 #include <rtabmap/utilite/ULogger.h>
00030 #include <rtabmap/utilite/UMath.h>
00031 #include <rtabmap/core/Compression.h>
00032 
00033 namespace rtabmap {
00034 
00035 Link::Link() :
00036         from_(0),
00037         to_(0),
00038         type_(kUndef),
00039         infMatrix_(cv::Mat::eye(6,6,CV_64FC1))
00040 {
00041 }
00042 Link::Link(int from,
00043                 int to,
00044                 Type type,
00045                 const Transform & transform,
00046                 const cv::Mat & infMatrix,
00047                 const cv::Mat & userData) :
00048         from_(from),
00049         to_(to),
00050         transform_(transform),
00051         type_(type)
00052 {
00053         setInfMatrix(infMatrix);
00054 
00055         if(userData.type() == CV_8UC1) // Bytes
00056         {
00057                 _userDataCompressed = userData; // assume compressed
00058         }
00059         else
00060         {
00061                 _userDataRaw = userData;
00062         }
00063 }
00064 Link::Link(int from,
00065                 int to,
00066                 Type type,
00067                 const Transform & transform,
00068                 double rotVariance,
00069                 double transVariance,
00070                 const cv::Mat & userData) :
00071         from_(from),
00072         to_(to),
00073         transform_(transform),
00074         type_(type)
00075 {
00076         setVariance(rotVariance, transVariance);
00077 
00078         if(userData.type() == CV_8UC1) // Bytes
00079         {
00080                 _userDataCompressed = userData; // assume compressed
00081         }
00082         else
00083         {
00084                 _userDataRaw = userData;
00085         }
00086 }
00087 
00088 double Link::rotVariance() const
00089 {
00090         double min = uMin3(infMatrix_.at<double>(3,3), infMatrix_.at<double>(4,4), infMatrix_.at<double>(5,5));
00091         UASSERT(min > 0.0);
00092         return 1.0/min;
00093 }
00094 double Link::transVariance() const
00095 {
00096         double min = uMin3(infMatrix_.at<double>(0,0), infMatrix_.at<double>(1,1), infMatrix_.at<double>(2,2));
00097         UASSERT(min > 0.0);
00098         return 1.0/min;
00099 }
00100 
00101 void Link::setInfMatrix(const cv::Mat & infMatrix) {
00102         UASSERT(infMatrix.cols == 6 && infMatrix.rows == 6 && infMatrix.type() == CV_64FC1);
00103         UASSERT_MSG(uIsFinite(infMatrix.at<double>(0,0)) && infMatrix.at<double>(0,0)>0, "Transitional information should not be null! (set to 1 if unknown)");
00104         UASSERT_MSG(uIsFinite(infMatrix.at<double>(1,1)) && infMatrix.at<double>(1,1)>0, "Transitional information should not be null! (set to 1 if unknown)");
00105         UASSERT_MSG(uIsFinite(infMatrix.at<double>(2,2)) && infMatrix.at<double>(2,2)>0, "Transitional information should not be null! (set to 1 if unknown)");
00106         UASSERT_MSG(uIsFinite(infMatrix.at<double>(3,3)) && infMatrix.at<double>(3,3)>0, "Rotational information should not be null! (set to 1 if unknown)");
00107         UASSERT_MSG(uIsFinite(infMatrix.at<double>(4,4)) && infMatrix.at<double>(4,4)>0, "Rotational information should not be null! (set to 1 if unknown)");
00108         UASSERT_MSG(uIsFinite(infMatrix.at<double>(5,5)) && infMatrix.at<double>(5,5)>0, "Rotational information should not be null! (set to 1 if unknown)");
00109         infMatrix_ = infMatrix;
00110 }
00111 void Link::setVariance(double rotVariance, double transVariance) {
00112         UASSERT(uIsFinite(rotVariance) && rotVariance>0);
00113         UASSERT(uIsFinite(transVariance) && transVariance>0);
00114         infMatrix_ = cv::Mat::eye(6,6,CV_64FC1);
00115         infMatrix_.at<double>(0,0) = 1.0/transVariance;
00116         infMatrix_.at<double>(1,1) = 1.0/transVariance;
00117         infMatrix_.at<double>(2,2) = 1.0/transVariance;
00118         infMatrix_.at<double>(3,3) = 1.0/rotVariance;
00119         infMatrix_.at<double>(4,4) = 1.0/rotVariance;
00120         infMatrix_.at<double>(5,5) = 1.0/rotVariance;
00121 }
00122 
00123 void Link::setUserDataRaw(const cv::Mat & userDataRaw)
00124 {
00125         if(!_userDataRaw.empty())
00126         {
00127                 UWARN("Writing new user data over existing user data. This may result in data loss.");
00128         }
00129         _userDataRaw = userDataRaw;
00130 }
00131 
00132 void Link::setUserData(const cv::Mat & userData)
00133 {
00134         if(!userData.empty() && (!_userDataCompressed.empty() || !_userDataRaw.empty()))
00135         {
00136                 UWARN("Writing new user data over existing user data. This may result in data loss.");
00137         }
00138         _userDataRaw = cv::Mat();
00139         _userDataCompressed = cv::Mat();
00140 
00141         if(!userData.empty())
00142         {
00143                 if(userData.type() == CV_8UC1) // Bytes
00144                 {
00145                         _userDataCompressed = userData; // assume compressed
00146                 }
00147                 else
00148                 {
00149                         _userDataRaw = userData;
00150                         _userDataCompressed = compressData2(userData);
00151                 }
00152         }
00153 }
00154 
00155 void Link::uncompressUserData()
00156 {
00157         cv::Mat dataRaw = uncompressUserDataConst();
00158         if(!dataRaw.empty() && _userDataRaw.empty())
00159         {
00160                 _userDataRaw = dataRaw;
00161         }
00162 }
00163 
00164 cv::Mat Link::uncompressUserDataConst() const
00165 {
00166         if(!_userDataRaw.empty())
00167         {
00168                 return _userDataRaw;
00169         }
00170         return uncompressData(_userDataCompressed);
00171 }
00172 
00173 Link Link::merge(const Link & link, Type outputType) const
00174 {
00175         UASSERT(to_ == link.from());
00176         UASSERT(outputType != Link::kUndef);
00177         UASSERT((link.transform().isNull() && transform_.isNull()) || (!link.transform().isNull() && !transform_.isNull()));
00178         UASSERT(infMatrix_.cols == 6 && infMatrix_.rows == 6 && infMatrix_.type() == CV_64FC1);
00179         UASSERT(link.infMatrix().cols == 6 && link.infMatrix().rows == 6 && link.infMatrix().type() == CV_64FC1);
00180         return Link(
00181                         from_,
00182                         link.to(),
00183                         outputType,
00184                         transform_.isNull()?Transform():transform_ * link.transform(), // FIXME, should be inf1^-1(inf1*t1 + inf2*t2)
00185                         transform_.isNull()?cv::Mat::eye(6,6,CV_64FC1):infMatrix_ + link.infMatrix());
00186 }
00187 
00188 Link Link::inverse() const
00189 {
00190         return Link(
00191                         to_,
00192                         from_,
00193                         type_,
00194                         transform_.isNull()?Transform():transform_.inverse(),
00195                         transform_.isNull()?cv::Mat::eye(6,6,CV_64FC1):infMatrix_);
00196 }
00197 
00198 }


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