Registration.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/RegistrationVis.h>
00030 #include <rtabmap/core/RegistrationIcp.h>
00031 #include <rtabmap/utilite/ULogger.h>
00032 #include <rtabmap/utilite/UTimer.h>
00033 
00034 namespace rtabmap {
00035 
00036 double Registration::COVARIANCE_EPSILON = 0.000000001;
00037 
00038 Registration * Registration::create(const ParametersMap & parameters)
00039 {
00040         int regTypeInt = Parameters::defaultRegStrategy();
00041         Parameters::parse(parameters, Parameters::kRegStrategy(), regTypeInt);
00042         Registration::Type type = (Registration::Type)regTypeInt;
00043         return create(type, parameters);
00044 }
00045 
00046 Registration * Registration::create(Registration::Type & type, const ParametersMap & parameters)
00047 {
00048         UDEBUG("type=%d", (int)type);
00049         Registration * reg = 0;
00050         switch(type)
00051         {
00052         case Registration::kTypeIcp:
00053                 reg = new RegistrationIcp(parameters);
00054                 break;
00055         case Registration::kTypeVisIcp:
00056                 reg = new RegistrationVis(parameters, new RegistrationIcp(parameters));
00057                 break;
00058         default: // kTypeVis
00059                 reg = new RegistrationVis(parameters);
00060                 type = Registration::kTypeVis;
00061                 break;
00062         }
00063         return reg;
00064 }
00065 
00066 Registration::Registration(const ParametersMap & parameters, Registration * child) :
00067         repeatOnce_(Parameters::defaultRegRepeatOnce()),
00068         force3DoF_(Parameters::defaultRegForce3DoF()),
00069         child_(child)
00070 {
00071         this->parseParameters(parameters);
00072 }
00073 
00074 Registration::~Registration()
00075 {
00076         delete child_;
00077 }
00078 void Registration::parseParameters(const ParametersMap & parameters)
00079 {
00080         Parameters::parse(parameters, Parameters::kRegRepeatOnce(), repeatOnce_);
00081         Parameters::parse(parameters, Parameters::kRegForce3DoF(), force3DoF_);
00082 
00083         if(child_)
00084         {
00085                 child_->parseParameters(parameters);
00086         }
00087 }
00088 
00089 bool Registration::isImageRequired() const
00090 {
00091         bool val = isImageRequiredImpl();
00092         if(!val && child_)
00093         {
00094                 val = child_->isImageRequired();
00095         }
00096         return val;
00097 }
00098 
00099 bool Registration::isScanRequired() const
00100 {
00101         bool val = isScanRequiredImpl();
00102         if(!val && child_)
00103         {
00104                 val = child_->isScanRequired();
00105         }
00106         return val;
00107 }
00108 
00109 bool Registration::isUserDataRequired() const
00110 {
00111         bool val = isUserDataRequiredImpl();
00112         if(!val && child_)
00113         {
00114                 val = child_->isUserDataRequired();
00115         }
00116         return val;
00117 }
00118 
00119 bool Registration::canUseGuess() const
00120 {
00121         bool val = canUseGuessImpl();
00122         if(!val && child_)
00123         {
00124                 val = child_->canUseGuess();
00125         }
00126         return val;
00127 }
00128 
00129 int Registration::getMinVisualCorrespondences() const
00130 {
00131         int min = this->getMinVisualCorrespondencesImpl();
00132         if(child_)
00133         {
00134                 int childMin = child_->getMinVisualCorrespondences();
00135                 if(min == 0 || childMin > min)
00136                 {
00137                         min = childMin;
00138                 }
00139         }
00140         return min;
00141 }
00142 
00143 float Registration::getMinGeometryCorrespondencesRatio() const
00144 {
00145         float min = this->getMinGeometryCorrespondencesRatioImpl();
00146         if(child_)
00147         {
00148                 float childMin = child_->getMinGeometryCorrespondencesRatio();
00149                 if(min == 0 || childMin > min)
00150                 {
00151                         min = childMin;
00152                 }
00153         }
00154         return min;
00155 }
00156 
00157 void Registration::setChildRegistration(Registration * child)
00158 {
00159         if(child_)
00160         {
00161                 delete child_;
00162         }
00163         child_ = child;
00164 }
00165 
00166 Transform Registration::computeTransformation(
00167                 const Signature & from,
00168                 const Signature & to,
00169                 Transform guess,
00170                 RegistrationInfo * infoOut) const
00171 {
00172         Signature fromCopy(from);
00173         Signature toCopy(to);
00174         return computeTransformationMod(fromCopy, toCopy, guess, infoOut);
00175 }
00176 
00177 Transform Registration::computeTransformation(
00178                 const SensorData & from,
00179                 const SensorData & to,
00180                 Transform guess,
00181                 RegistrationInfo * infoOut) const
00182 {
00183         Signature fromCopy(from);
00184         Signature toCopy(to);
00185         return computeTransformationMod(fromCopy, toCopy, guess, infoOut);
00186 }
00187 
00188 Transform Registration::computeTransformationMod(
00189                 Signature & from,
00190                 Signature & to,
00191                 Transform guess,
00192                 RegistrationInfo * infoOut) const
00193 {
00194         UTimer time;
00195         RegistrationInfo info;
00196         if(infoOut)
00197         {
00198                 info = *infoOut;
00199         }
00200 
00201         if(!guess.isNull() && force3DoF_)
00202         {
00203                 guess = guess.to3DoF();
00204         }
00205 
00206         Transform t = computeTransformationImpl(from, to, guess, info);
00207 
00208         if(child_)
00209         {
00210                 if(!t.isNull())
00211                 {
00212                         t = child_->computeTransformationMod(from, to, force3DoF_?t.to3DoF():t, &info);
00213                 }
00214                 else if(!guess.isNull())
00215                 {
00216                         UDEBUG("This registration approach failed, continue with the guess for the next registration");
00217                         t = child_->computeTransformationMod(from, to, guess, &info);
00218                 }
00219         }
00220         else if(repeatOnce_ && guess.isNull() && !t.isNull() && this->canUseGuess())
00221         {
00222                 // redo with guess to get a more accurate transform
00223                 t = computeTransformationImpl(from, to, t, info);
00224 
00225                 if(!t.isNull() && force3DoF_)
00226                 {
00227                         t = t.to3DoF();
00228                 }
00229         }
00230         else if(!t.isNull() && force3DoF_)
00231         {
00232                 t = t.to3DoF();
00233         }
00234 
00235         if(info.covariance.empty())
00236         {
00237                 info.covariance = cv::Mat::eye(6,6,CV_64FC1);
00238         }
00239 
00240         if(info.covariance.at<double>(0,0)<=COVARIANCE_EPSILON)
00241                 info.covariance.at<double>(0,0) = COVARIANCE_EPSILON; // epsilon if exact transform
00242         if(info.covariance.at<double>(1,1)<=COVARIANCE_EPSILON)
00243                 info.covariance.at<double>(1,1) = COVARIANCE_EPSILON; // epsilon if exact transform
00244         if(info.covariance.at<double>(2,2)<=COVARIANCE_EPSILON)
00245                 info.covariance.at<double>(2,2) = COVARIANCE_EPSILON; // epsilon if exact transform
00246         if(info.covariance.at<double>(3,3)<=COVARIANCE_EPSILON)
00247                 info.covariance.at<double>(3,3) = COVARIANCE_EPSILON; // epsilon if exact transform
00248         if(info.covariance.at<double>(4,4)<=COVARIANCE_EPSILON)
00249                 info.covariance.at<double>(4,4) = COVARIANCE_EPSILON; // epsilon if exact transform
00250         if(info.covariance.at<double>(5,5)<=COVARIANCE_EPSILON)
00251                 info.covariance.at<double>(5,5) = COVARIANCE_EPSILON; // epsilon if exact transform
00252 
00253 
00254         if(infoOut)
00255         {
00256                 *infoOut = info;
00257                 infoOut->totalTime = time.ticks();
00258         }
00259         return t;
00260 }
00261 
00262 }


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