OdometryF2F.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/OdometryF2F.h"
00029 #include "rtabmap/core/OdometryInfo.h"
00030 #include "rtabmap/core/Registration.h"
00031 #include "rtabmap/core/EpipolarGeometry.h"
00032 #include "rtabmap/core/util3d_transforms.h"
00033 #include "rtabmap/utilite/ULogger.h"
00034 #include "rtabmap/utilite/UTimer.h"
00035 #include "rtabmap/utilite/UStl.h"
00036 
00037 namespace rtabmap {
00038 
00039 OdometryF2F::OdometryF2F(const ParametersMap & parameters) :
00040         Odometry(parameters),
00041         keyFrameThr_(Parameters::defaultOdomKeyFrameThr()),
00042         visKeyFrameThr_(Parameters::defaultOdomVisKeyFrameThr()),
00043         scanKeyFrameThr_(Parameters::defaultOdomScanKeyFrameThr())
00044 {
00045         registrationPipeline_ = Registration::create(parameters);
00046         Parameters::parse(parameters, Parameters::kOdomKeyFrameThr(), keyFrameThr_);
00047         Parameters::parse(parameters, Parameters::kOdomVisKeyFrameThr(), visKeyFrameThr_);
00048         Parameters::parse(parameters, Parameters::kOdomScanKeyFrameThr(), scanKeyFrameThr_);
00049         UASSERT(keyFrameThr_>=0.0f && keyFrameThr_<=1.0f);
00050         UASSERT(visKeyFrameThr_>=0);
00051         UASSERT(scanKeyFrameThr_>=0.0f && scanKeyFrameThr_<=1.0f);
00052 
00053         parameters_ = parameters;
00054 }
00055 
00056 OdometryF2F::~OdometryF2F()
00057 {
00058         delete registrationPipeline_;
00059 }
00060 
00061 void OdometryF2F::reset(const Transform & initialPose)
00062 {
00063         Odometry::reset(initialPose);
00064         refFrame_ = Signature();
00065         lastKeyFramePose_.setNull();
00066 }
00067 
00068 // return not null transform if odometry is correctly computed
00069 Transform OdometryF2F::computeTransform(
00070                 SensorData & data,
00071                 const Transform & guess,
00072                 OdometryInfo * info)
00073 {
00074         UTimer timer;
00075         Transform output;
00076         if(!data.rightRaw().empty() && !data.stereoCameraModel().isValidForProjection())
00077         {
00078                 UERROR("Calibrated stereo camera required");
00079                 return output;
00080         }
00081         if(!data.depthRaw().empty() &&
00082                 (data.cameraModels().size() != 1 || !data.cameraModels()[0].isValidForProjection()))
00083         {
00084                 UERROR("Calibrated camera required (multi-cameras not supported).");
00085                 return output;
00086         }
00087 
00088         bool addKeyFrame = false;
00089         RegistrationInfo regInfo;
00090 
00091         UASSERT(!this->getPose().isNull());
00092         if(lastKeyFramePose_.isNull())
00093         {
00094                 lastKeyFramePose_ = this->getPose(); // reset to current pose
00095         }
00096         Transform motionSinceLastKeyFrame = lastKeyFramePose_.inverse()*this->getPose();
00097 
00098         Signature newFrame(data);
00099         if(refFrame_.sensorData().isValid())
00100         {
00101                 float maxCorrespondenceDistance = 0.0f;
00102                 float pmOutlierRatio = 0.0f;
00103                 if(guess.isNull() &&
00104                         !registrationPipeline_->isImageRequired() &&
00105                         registrationPipeline_->isScanRequired() &&
00106                         this->framesProcessed() < 2)
00107                 {
00108                         // only on initialization (first frame to register), increase icp max correspondences in case the robot is already moving
00109                         maxCorrespondenceDistance = Parameters::defaultIcpMaxCorrespondenceDistance();
00110                         pmOutlierRatio = Parameters::defaultIcpPMOutlierRatio();
00111                         Parameters::parse(parameters_, Parameters::kIcpMaxCorrespondenceDistance(), maxCorrespondenceDistance);
00112                         Parameters::parse(parameters_, Parameters::kIcpPMOutlierRatio(), pmOutlierRatio);
00113                         ParametersMap params;
00114                         params.insert(ParametersPair(Parameters::kIcpMaxCorrespondenceDistance(), uNumber2Str(maxCorrespondenceDistance*3.0f)));
00115                         params.insert(ParametersPair(Parameters::kIcpPMOutlierRatio(), uNumber2Str(0.95f)));
00116                         registrationPipeline_->parseParameters(params);
00117                 }
00118 
00119                 Signature tmpRefFrame = refFrame_;
00120                 output = registrationPipeline_->computeTransformationMod(
00121                                 tmpRefFrame,
00122                                 newFrame,
00123                                 // special case for ICP-only odom, set guess to identity if we just started or reset
00124                                 !guess.isNull()?motionSinceLastKeyFrame*guess:!registrationPipeline_->isImageRequired()&&this->framesProcessed()<2?motionSinceLastKeyFrame:Transform(),
00125                                 &regInfo);
00126 
00127                 if(maxCorrespondenceDistance>0.0f)
00128                 {
00129                         // set it back
00130                         ParametersMap params;
00131                         params.insert(ParametersPair(Parameters::kIcpMaxCorrespondenceDistance(), uNumber2Str(maxCorrespondenceDistance)));
00132                         params.insert(ParametersPair(Parameters::kIcpPMOutlierRatio(), uNumber2Str(pmOutlierRatio)));
00133                         registrationPipeline_->parseParameters(params);
00134                 }
00135 
00136                 if(output.isNull() && !guess.isNull() && registrationPipeline_->isImageRequired())
00137                 {
00138                         tmpRefFrame = refFrame_;
00139                         // reset matches, but keep already extracted features in newFrame.sensorData()
00140                         newFrame.setWords(std::multimap<int, cv::KeyPoint>());
00141                         newFrame.setWords3(std::multimap<int, cv::Point3f>());
00142                         newFrame.setWordsDescriptors(std::multimap<int, cv::Mat>());
00143                         UWARN("Failed to find a transformation with the provided guess (%s), trying again without a guess.", guess.prettyPrint().c_str());
00144                         // If optical flow is used, switch temporary to feature matching
00145                         int visCorTypeBackup = Parameters::defaultVisCorType();
00146                         Parameters::parse(parameters_, Parameters::kVisCorType(), visCorTypeBackup);
00147                         if(visCorTypeBackup == 1)
00148                         {
00149                                 ParametersMap params;
00150                                 params.insert(ParametersPair(Parameters::kVisCorType(), "0"));
00151                                 registrationPipeline_->parseParameters(params);
00152                         }
00153 
00154                         output = registrationPipeline_->computeTransformationMod(
00155                                 tmpRefFrame,
00156                                 newFrame,
00157                                 Transform(), // null guess
00158                                 &regInfo);
00159 
00160                         if(visCorTypeBackup == 1)
00161                         {
00162                                 ParametersMap params;
00163                                 params.insert(ParametersPair(Parameters::kVisCorType(), "1"));
00164                                 registrationPipeline_->parseParameters(params);
00165                         }
00166 
00167                         if(output.isNull())
00168                         {
00169                                 UWARN("Trial with no guess still fail.");
00170                         }
00171                         else
00172                         {
00173                                 UWARN("Trial with no guess succeeded.");
00174                         }
00175                 }
00176 
00177                 if(info && this->isInfoDataFilled())
00178                 {
00179                         std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > pairs;
00180                         EpipolarGeometry::findPairsUnique(tmpRefFrame.getWords(), newFrame.getWords(), pairs);
00181                         info->refCorners.resize(pairs.size());
00182                         info->newCorners.resize(pairs.size());
00183                         std::map<int, int> idToIndex;
00184                         int i=0;
00185                         for(std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > >::iterator iter=pairs.begin();
00186                                 iter!=pairs.end();
00187                                 ++iter)
00188                         {
00189                                 info->refCorners[i] = iter->second.first.pt;
00190                                 info->newCorners[i] = iter->second.second.pt;
00191                                 idToIndex.insert(std::make_pair(iter->first, i));
00192                                 ++i;
00193                         }
00194                         info->cornerInliers.resize(regInfo.inliersIDs.size(), 1);
00195                         i=0;
00196                         for(; i<(int)regInfo.inliersIDs.size(); ++i)
00197                         {
00198                                 info->cornerInliers[i] = idToIndex.at(regInfo.inliersIDs[i]);
00199                         }
00200 
00201                         Transform t = this->getPose()*motionSinceLastKeyFrame.inverse();
00202                         for(std::multimap<int, cv::Point3f>::const_iterator iter=tmpRefFrame.getWords3().begin(); iter!=tmpRefFrame.getWords3().end(); ++iter)
00203                         {
00204                                 info->localMap.insert(std::make_pair(iter->first, util3d::transformPoint(iter->second, t)));
00205                         }
00206                         info->localMapSize = tmpRefFrame.getWords3().size();
00207                         info->words = newFrame.getWords();
00208 
00209                         info->localScanMapSize = tmpRefFrame.sensorData().laserScanRaw().size();
00210 
00211                         info->localScanMap = util3d::transformLaserScan(tmpRefFrame.sensorData().laserScanRaw(), tmpRefFrame.sensorData().laserScanRaw().localTransform().inverse()*t*tmpRefFrame.sensorData().laserScanRaw().localTransform());
00212                 }
00213         }
00214         else
00215         {
00216                 //return Identity
00217                 output = Transform::getIdentity();
00218                 // a very high variance tells that the new pose is not linked with the previous one
00219                 regInfo.covariance = cv::Mat::eye(6,6,CV_64FC1)*9999.0;
00220         }
00221 
00222         if(!output.isNull())
00223         {
00224                 output = motionSinceLastKeyFrame.inverse() * output;
00225 
00226                 // new key-frame?
00227                 if( (registrationPipeline_->isImageRequired() &&
00228                                 (keyFrameThr_ == 0.0f ||
00229                                  visKeyFrameThr_ == 0 ||
00230                                  float(regInfo.inliers) <= keyFrameThr_*float(refFrame_.sensorData().keypoints().size()) ||
00231                                  regInfo.inliers <= visKeyFrameThr_)) ||
00232                         (registrationPipeline_->isScanRequired() && (scanKeyFrameThr_ == 0.0f || regInfo.icpInliersRatio <= scanKeyFrameThr_)))
00233                 {
00234                         UDEBUG("Update key frame");
00235                         int features = newFrame.getWordsDescriptors().size();
00236                         if(registrationPipeline_->isImageRequired() && features == 0)
00237                         {
00238                                 newFrame = Signature(data);
00239                                 // this will generate features only for the first frame or if optical flow was used (no 3d words)
00240                                 Signature dummy;
00241                                 registrationPipeline_->computeTransformationMod(
00242                                                 newFrame,
00243                                                 dummy);
00244                                 features = (int)newFrame.sensorData().keypoints().size();
00245                         }
00246 
00247                         if((features >= registrationPipeline_->getMinVisualCorrespondences()) &&
00248                            (registrationPipeline_->getMinGeometryCorrespondencesRatio()==0.0f ||
00249                                            (newFrame.sensorData().laserScanRaw().size() &&
00250                                            (newFrame.sensorData().laserScanRaw().maxPoints() == 0 || float(newFrame.sensorData().laserScanRaw().size())/float(newFrame.sensorData().laserScanRaw().maxPoints())>=registrationPipeline_->getMinGeometryCorrespondencesRatio()))))
00251                         {
00252                                 refFrame_ = newFrame;
00253 
00254                                 refFrame_.setWords(std::multimap<int, cv::KeyPoint>());
00255                                 refFrame_.setWords3(std::multimap<int, cv::Point3f>());
00256                                 refFrame_.setWordsDescriptors(std::multimap<int, cv::Mat>());
00257 
00258                                 //reset motion
00259                                 lastKeyFramePose_.setNull();
00260 
00261                                 addKeyFrame = true;
00262                         }
00263                         else
00264                         {
00265                                 if (!refFrame_.sensorData().isValid())
00266                                 {
00267                                         // Don't send odometry if we don't have a keyframe yet
00268                                         output.setNull();
00269                                 }
00270 
00271                                 if(features < registrationPipeline_->getMinVisualCorrespondences())
00272                                 {
00273                                         UWARN("Too low 2D features (%d), keeping last key frame...", features);
00274                                 }
00275 
00276                                 if(registrationPipeline_->getMinGeometryCorrespondencesRatio()>0.0f && newFrame.sensorData().laserScanRaw().size()==0)
00277                                 {
00278                                         UWARN("Too low scan points (%d), keeping last key frame...", newFrame.sensorData().laserScanRaw().size());
00279                                 }
00280                                 else if(registrationPipeline_->getMinGeometryCorrespondencesRatio()>0.0f && newFrame.sensorData().laserScanRaw().maxPoints() != 0 && float(newFrame.sensorData().laserScanRaw().size())/float(newFrame.sensorData().laserScanRaw().maxPoints())<registrationPipeline_->getMinGeometryCorrespondencesRatio())
00281                                 {
00282                                         UWARN("Too low scan points ratio (%d < %d), keeping last key frame...", float(newFrame.sensorData().laserScanRaw().size())/float(newFrame.sensorData().laserScanRaw().maxPoints()), registrationPipeline_->getMinGeometryCorrespondencesRatio());
00283                                 }
00284                         }
00285                 }
00286         }
00287         else if(!regInfo.rejectedMsg.empty())
00288         {
00289                 UWARN("Registration failed: \"%s\"", regInfo.rejectedMsg.c_str());
00290         }
00291 
00292         data.setFeatures(newFrame.sensorData().keypoints(), newFrame.sensorData().keypoints3D(), newFrame.sensorData().descriptors());
00293 
00294         if(info)
00295         {
00296                 info->type = kTypeF2F;
00297                 info->features = newFrame.sensorData().keypoints().size();
00298                 info->keyFrameAdded = addKeyFrame;
00299                 if(this->isInfoDataFilled())
00300                 {
00301                         info->reg = regInfo;
00302                 }
00303                 else
00304                 {
00305                         info->reg = regInfo.copyWithoutData();
00306                 }
00307         }
00308 
00309         UINFO("Odom update time = %fs lost=%s inliers=%d, ref frame corners=%d, transform accepted=%s",
00310                         timer.elapsed(),
00311                         output.isNull()?"true":"false",
00312                         (int)regInfo.inliers,
00313                         (int)newFrame.sensorData().keypoints().size(),
00314                         !output.isNull()?"true":"false");
00315 
00316         return output;
00317 }
00318 
00319 } // namespace rtabmap


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