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 
00033 namespace rtabmap {
00034 
00035 Registration * Registration::create(const ParametersMap & parameters)
00036 {
00037         int regTypeInt = Parameters::defaultRegStrategy();
00038         Parameters::parse(parameters, Parameters::kRegStrategy(), regTypeInt);
00039         Registration::Type type = (Registration::Type)regTypeInt;
00040         return create(type, parameters);
00041 }
00042 
00043 Registration * Registration::create(Registration::Type & type, const ParametersMap & parameters)
00044 {
00045         UDEBUG("type=%d", (int)type);
00046         Registration * reg = 0;
00047         switch(type)
00048         {
00049         case Registration::kTypeIcp:
00050                 reg = new RegistrationIcp(parameters);
00051                 break;
00052         case Registration::kTypeVisIcp:
00053                 reg = new RegistrationVis(parameters, new RegistrationIcp(parameters));
00054                 break;
00055         default: // kTypeVis
00056                 reg = new RegistrationVis(parameters);
00057                 type = Registration::kTypeVis;
00058                 break;
00059         }
00060         return reg;
00061 }
00062 
00063 Registration::Registration(const ParametersMap & parameters, Registration * child) :
00064         varianceFromInliersCount_(Parameters::defaultRegVarianceFromInliersCount()),
00065         force3DoF_(Parameters::defaultRegForce3DoF()),
00066         child_(child)
00067 {
00068         this->parseParameters(parameters);
00069 }
00070 
00071 Registration::~Registration()
00072 {
00073         if(child_)
00074         {
00075                 delete child_;
00076         }
00077 }
00078 void Registration::parseParameters(const ParametersMap & parameters)
00079 {
00080         Parameters::parse(parameters, Parameters::kRegVarianceFromInliersCount(), varianceFromInliersCount_);
00081         Parameters::parse(parameters, Parameters::kRegForce3DoF(), force3DoF_);
00082         if(child_)
00083         {
00084                 child_->parseParameters(parameters);
00085         }
00086 }
00087 
00088 bool Registration::isImageRequired() const
00089 {
00090         bool val = isImageRequiredImpl();
00091         if(!val && child_)
00092         {
00093                 val = child_->isImageRequired();
00094         }
00095         return val;
00096 }
00097 
00098 bool Registration::isScanRequired() const
00099 {
00100         bool val = isScanRequiredImpl();
00101         if(!val && child_)
00102         {
00103                 val = child_->isScanRequired();
00104         }
00105         return val;
00106 }
00107 
00108 bool Registration::isUserDataRequired() const
00109 {
00110         bool val = isUserDataRequiredImpl();
00111         if(!val && child_)
00112         {
00113                 val = child_->isUserDataRequired();
00114         }
00115         return val;
00116 }
00117 
00118 int Registration::getMinVisualCorrespondences() const
00119 {
00120         int min = this->getMinVisualCorrespondencesImpl();
00121         if(child_)
00122         {
00123                 int childMin = child_->getMinVisualCorrespondences();
00124                 if(min == 0 || childMin > min)
00125                 {
00126                         min = childMin;
00127                 }
00128         }
00129         return min;
00130 }
00131 
00132 float Registration::getMinGeometryCorrespondencesRatio() const
00133 {
00134         float min = this->getMinGeometryCorrespondencesRatioImpl();
00135         if(child_)
00136         {
00137                 float childMin = child_->getMinGeometryCorrespondencesRatio();
00138                 if(min == 0 || childMin > min)
00139                 {
00140                         min = childMin;
00141                 }
00142         }
00143         return min;
00144 }
00145 
00146 void Registration::setChildRegistration(Registration * child)
00147 {
00148         if(child_)
00149         {
00150                 delete child_;
00151         }
00152         child_ = child;
00153 }
00154 
00155 Transform Registration::computeTransformation(
00156                 const Signature & from,
00157                 const Signature & to,
00158                 Transform guess,
00159                 RegistrationInfo * infoOut) const
00160 {
00161         Signature fromCopy(from);
00162         Signature toCopy(to);
00163         return computeTransformationMod(fromCopy, toCopy, guess, infoOut);
00164 }
00165 
00166 Transform Registration::computeTransformation(
00167                 const SensorData & from,
00168                 const SensorData & 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::computeTransformationMod(
00178                 Signature & from,
00179                 Signature & to,
00180                 Transform guess,
00181                 RegistrationInfo * infoOut) const
00182 {
00183         RegistrationInfo info;
00184         if(infoOut)
00185         {
00186                 info = *infoOut;
00187         }
00188 
00189         if(!guess.isNull() && force3DoF_)
00190         {
00191                 guess = guess.to3DoF();
00192         }
00193 
00194         Transform t = computeTransformationImpl(from, to, guess, info);
00195 
00196         if(varianceFromInliersCount_)
00197         {
00198                 if(info.icpInliersRatio)
00199                 {
00200                         info.variance = info.icpInliersRatio > 0?1.0/double(info.icpInliersRatio):1.0;
00201                 }
00202                 else
00203                 {
00204                         info.variance = info.inliers > 0?1.0f/float(info.inliers):1.0f;
00205                 }
00206                 info.variance = info.variance>0.0f?info.variance:0.0001f; // epsilon if exact transform
00207         }
00208 
00209         if(child_)
00210         {
00211                 if(!t.isNull())
00212                 {
00213                         t = child_->computeTransformationMod(from, to, force3DoF_?t.to3DoF():t, &info);
00214                 }
00215                 else if(!guess.isNull())
00216                 {
00217                         UDEBUG("This registration approach failed, continue with the guess for the next registration");
00218                         t = child_->computeTransformationMod(from, to, guess, &info);
00219                 }
00220         }
00221         else if(!t.isNull() && force3DoF_)
00222         {
00223                 t = t.to3DoF();
00224         }
00225 
00226         if(infoOut)
00227         {
00228                 *infoOut = info;
00229         }
00230         return t;
00231 }
00232 
00233 }


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