OdometryF2M.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/OdometryInfo.h"
00029 #include "rtabmap/core/Memory.h"
00030 #include "rtabmap/core/VisualWord.h"
00031 #include "rtabmap/core/Signature.h"
00032 #include "rtabmap/core/RegistrationVis.h"
00033 #include "rtabmap/core/util3d_transforms.h"
00034 #include "rtabmap/core/util3d_registration.h"
00035 #include "rtabmap/core/util3d_correspondences.h"
00036 #include "rtabmap/core/util3d_motion_estimation.h"
00037 #include "rtabmap/core/util3d_filtering.h"
00038 #include "rtabmap/core/Optimizer.h"
00039 #include "rtabmap/core/VWDictionary.h"
00040 #include "rtabmap/core/util3d.h"
00041 #include "rtabmap/utilite/ULogger.h"
00042 #include "rtabmap/utilite/UTimer.h"
00043 #include "rtabmap/utilite/UMath.h"
00044 #include "rtabmap/utilite/UConversion.h"
00045 #include <opencv2/calib3d/calib3d.hpp>
00046 #include <rtabmap/core/OdometryF2M.h>
00047 #include <pcl/common/io.h>
00048 
00049 #if _MSC_VER
00050         #define ISFINITE(value) _finite(value)
00051 #else
00052         #define ISFINITE(value) std::isfinite(value)
00053 #endif
00054 
00055 namespace rtabmap {
00056 
00057 OdometryF2M::OdometryF2M(const ParametersMap & parameters) :
00058         Odometry(parameters),
00059         maximumMapSize_(Parameters::defaultOdomF2MMaxSize()),
00060         keyFrameThr_(Parameters::defaultOdomKeyFrameThr()),
00061         maxNewFeatures_(Parameters::defaultOdomF2MMaxNewFeatures()),
00062         scanKeyFrameThr_(Parameters::defaultOdomScanKeyFrameThr()),
00063         scanMaximumMapSize_(Parameters::defaultOdomF2MScanMaxSize()),
00064         scanSubtractRadius_(Parameters::defaultOdomF2MScanSubtractRadius()),
00065         fixedMapPath_(Parameters::defaultOdomF2MFixedMapPath()),
00066         regPipeline_(Registration::create(parameters)),
00067         map_(new Signature(-1)),
00068         lastFrame_(new Signature(1))
00069 {
00070         UDEBUG("");
00071         Parameters::parse(parameters, Parameters::kOdomF2MMaxSize(), maximumMapSize_);
00072         Parameters::parse(parameters, Parameters::kOdomKeyFrameThr(), keyFrameThr_);
00073         Parameters::parse(parameters, Parameters::kOdomF2MMaxNewFeatures(), maxNewFeatures_);
00074         Parameters::parse(parameters, Parameters::kOdomScanKeyFrameThr(), scanKeyFrameThr_);
00075         Parameters::parse(parameters, Parameters::kOdomF2MScanMaxSize(), scanMaximumMapSize_);
00076         Parameters::parse(parameters, Parameters::kOdomF2MScanSubtractRadius(), scanSubtractRadius_);
00077         Parameters::parse(parameters, Parameters::kOdomF2MFixedMapPath(), fixedMapPath_);
00078         UASSERT(maximumMapSize_ >= 0);
00079         UASSERT(keyFrameThr_ >= 0.0f && keyFrameThr_<=1.0f);
00080         UASSERT(scanKeyFrameThr_ >= 0.0f && scanKeyFrameThr_<=1.0f);
00081         UASSERT(maxNewFeatures_ >= 0);
00082 
00083         if(!fixedMapPath_.empty())
00084         {
00085                 UINFO("Init odometry from a fixed database: \"%s\"", fixedMapPath_.c_str());
00086                 // init the local map with a all 3D features contained in the database
00087                 ParametersMap customParameters;
00088                 customParameters.insert(ParametersPair(Parameters::kMemIncrementalMemory(), "false"));
00089                 customParameters.insert(ParametersPair(Parameters::kMemInitWMWithAllNodes(), "true"));
00090                 customParameters.insert(ParametersPair(Parameters::kMemSTMSize(), "0"));
00091                 Memory memory(customParameters);
00092                 if(!memory.init(fixedMapPath_, false, ParametersMap()))
00093                 {
00094                         UERROR("Error initializing the memory for BOW Odometry.");
00095                 }
00096                 else
00097                 {
00098                         // get the graph
00099                         std::map<int, int> ids = memory.getNeighborsId(memory.getLastSignatureId(), 0, -1);
00100                         std::map<int, Transform> poses;
00101                         std::multimap<int, Link> links;
00102                         memory.getMetricConstraints(uKeysSet(ids), poses, links, true);
00103 
00104                         if(poses.size())
00105                         {
00106                                 //optimize the graph
00107                                 Optimizer * optimizer = Optimizer::create(parameters);
00108                                 std::map<int, Transform> optimizedPoses = optimizer->optimize(poses.begin()->first, poses, links);
00109                                 delete optimizer;
00110 
00111                                 std::multimap<int, cv::Point3f> words3D;
00112                                 std::multimap<int, cv::Mat> wordsDescriptors;
00113 
00114                                 // fill the local map
00115                                 for(std::map<int, Transform>::iterator posesIter=optimizedPoses.begin();
00116                                         posesIter!=optimizedPoses.end();
00117                                         ++posesIter)
00118                                 {
00119                                         const Signature * s = memory.getSignature(posesIter->first);
00120                                         if(s)
00121                                         {
00122                                                 // Transform 3D points accordingly to pose and add them to local map
00123                                                 for(std::multimap<int, cv::Point3f>::const_iterator pointsIter=s->getWords3().begin();
00124                                                         pointsIter!=s->getWords3().end();
00125                                                         ++pointsIter)
00126                                                 {
00127                                                         if(!uContains(words3D, pointsIter->first))
00128                                                         {
00129                                                                 words3D.insert(std::make_pair(pointsIter->first, util3d::transformPoint(pointsIter->second, posesIter->second)));
00130 
00131                                                                 if(s->getWordsDescriptors().size() == s->getWords3().size())
00132                                                                 {
00133                                                                         UASSERT(uContains(s->getWordsDescriptors(), pointsIter->first));
00134                                                                         wordsDescriptors.insert(std::make_pair(pointsIter->first, s->getWordsDescriptors().find(pointsIter->first)->second));
00135                                                                 }
00136                                                                 else // load descriptor from dictionary
00137                                                                 {
00138                                                                         UASSERT(memory.getVWDictionary()->getWord(pointsIter->first) != 0);
00139                                                                         wordsDescriptors.insert(std::make_pair(pointsIter->first, memory.getVWDictionary()->getWord(pointsIter->first)->getDescriptor()));
00140                                                                 }
00141                                                         }
00142                                                 }
00143                                         }
00144                                 }
00145                                 UASSERT(words3D.size() == wordsDescriptors.size());
00146                                 map_->setWords3(words3D);
00147                                 map_->setWordsDescriptors(wordsDescriptors);
00148                         }
00149                         else
00150                         {
00151                                 UERROR("No pose loaded from database \"%s\"", fixedMapPath_.c_str());
00152                         }
00153                 }
00154                 if((int)map_->getWords3().size() < regPipeline_->getMinVisualCorrespondences() || map_->getWords3().size() == 0)
00155                 {
00156                         // TODO: support geometric-only maps?
00157                         UERROR("The loaded fixed map from \"%s\" is too small! Only %d unique features loaded. Odometry won't be computed!",
00158                                         fixedMapPath_.c_str(), (int)map_->getWords3().size());
00159                 }
00160         }
00161 }
00162 
00163 OdometryF2M::~OdometryF2M()
00164 {
00165         delete map_;
00166         delete lastFrame_;
00167         UDEBUG("");
00168 }
00169 
00170 
00171 void OdometryF2M::reset(const Transform & initialPose)
00172 {
00173         Odometry::reset(initialPose);
00174         *lastFrame_ = Signature(1);
00175 
00176         if(fixedMapPath_.empty())
00177         {
00178                 *map_ = Signature(-1);
00179         }
00180         else
00181         {
00182                 UWARN("Odometry cannot be reset when a fixed local map is set.");
00183         }
00184 }
00185 
00186 // return not null transform if odometry is correctly computed
00187 Transform OdometryF2M::computeTransform(
00188                 SensorData & data,
00189                 const Transform & guess,
00190                 OdometryInfo * info)
00191 {
00192         UTimer timer;
00193         Transform output;
00194 
00195         if(info)
00196         {
00197                 info->type = 0;
00198         }
00199 
00200         RegistrationInfo regInfo;
00201         int nFeatures = 0;
00202 
00203         delete lastFrame_;
00204         lastFrame_ = new Signature(data);
00205 
00206         // Generate keypoints from the new data
00207         if(lastFrame_->sensorData().isValid())
00208         {
00209                 if((map_->getWords3().size() || !map_->sensorData().laserScanRaw().empty()) &&
00210                         lastFrame_->sensorData().isValid())
00211                 {
00212                         Signature tmpMap = *map_;
00213                         Transform transform = regPipeline_->computeTransformationMod(
00214                                         tmpMap,
00215                                         *lastFrame_,
00216                                         guess.isNull()?Transform():this->getPose()*guess,
00217                                         &regInfo);
00218 
00219                         data.setFeatures(lastFrame_->sensorData().keypoints(), lastFrame_->sensorData().descriptors());
00220 
00221                         if(!transform.isNull())
00222                         {
00223                                 // make it incremental
00224                                 transform = this->getPose().inverse() * transform;
00225                         }
00226                         else if(!regInfo.rejectedMsg.empty())
00227                         {
00228                                 UWARN("Registration failed: \"%s\"", regInfo.rejectedMsg.c_str());
00229                         }
00230                         else
00231                         {
00232                                 UWARN("Unknown registration error");
00233                         }
00234 
00235                         if(!transform.isNull())
00236                         {
00237                                 output = transform;
00238 
00239                                 if(fixedMapPath_.empty())
00240                                 {
00241                                         bool modified = false;
00242                                         Transform newFramePose = this->getPose()*output;
00243 
00244                                         // fields to update
00245                                         cv::Mat mapScan = tmpMap.sensorData().laserScanRaw();
00246                                         std::multimap<int, cv::KeyPoint> mapWords = tmpMap.getWords();
00247                                         std::multimap<int, cv::Point3f> mapPoints = tmpMap.getWords3();
00248                                         std::multimap<int, cv::Mat> mapDescriptors = tmpMap.getWordsDescriptors();
00249 
00250                                         //Visual
00251                                         int added = 0;
00252                                         int removed = 0;
00253                                         UDEBUG("keyframeThr=%f matches=%d inliers=%d features=%d mp=%d", keyFrameThr_, regInfo.matches, regInfo.inliers, (int)lastFrame_->sensorData().keypoints().size(), (int)mapPoints.size());
00254                                         if(regPipeline_->isImageRequired() &&
00255                                                 (keyFrameThr_==0 || float(regInfo.inliers) <= keyFrameThr_*float(lastFrame_->sensorData().keypoints().size())))
00256                                         {
00257                                                 UDEBUG("Update local map (ratio=%f < %f)", float(regInfo.inliers)/float(lastFrame_->sensorData().keypoints().size()), keyFrameThr_);
00258 
00259                                                 // update local map
00260                                                 UASSERT(mapWords.size() == mapPoints.size());
00261                                                 UASSERT(mapPoints.size() == mapDescriptors.size());
00262                                                 UASSERT_MSG(lastFrame_->getWordsDescriptors().size() == lastFrame_->getWords3().size(), uFormat("%d vs %d", lastFrame_->getWordsDescriptors().size(), lastFrame_->getWords3().size()).c_str());
00263 
00264                                                 // sort by feature response
00265                                                 std::multimap<float, std::pair<int, std::pair<cv::KeyPoint, std::pair<cv::Point3f, cv::Mat> > > > newIds;
00266                                                 UASSERT(lastFrame_->getWords3().size() == lastFrame_->getWords().size());
00267                                                 std::multimap<int, cv::KeyPoint>::const_iterator iter2D = lastFrame_->getWords().begin();
00268                                                 std::multimap<int, cv::Mat>::const_iterator iterDesc = lastFrame_->getWordsDescriptors().begin();
00269                                                 for(std::multimap<int, cv::Point3f>::const_iterator iter = lastFrame_->getWords3().begin(); iter!=lastFrame_->getWords3().end(); ++iter, ++iter2D, ++iterDesc)
00270                                                 {
00271                                                         if(util3d::isFinite(iter->second))
00272                                                         {
00273                                                                 if(mapPoints.find(iter->first) == mapPoints.end()) // Point not in map
00274                                                                 {
00275                                                                         newIds.insert(
00276                                                                                         std::make_pair(iter2D->second.response>0?1.0f/iter2D->second.response:0.0f,
00277                                                                                                         std::make_pair(iter->first,
00278                                                                                                                         std::make_pair(iter2D->second,
00279                                                                                                                                         std::make_pair(iter->second, iterDesc->second)))));
00280                                                                 }
00281                                                         }
00282                                                 }
00283 
00284                                                 for(std::multimap<float, std::pair<int, std::pair<cv::KeyPoint, std::pair<cv::Point3f, cv::Mat> > > >::iterator iter=newIds.begin();
00285                                                         iter!=newIds.end();
00286                                                         ++iter)
00287                                                 {
00288                                                         if(maxNewFeatures_ == 0  || added < maxNewFeatures_)
00289                                                         {
00290                                                                 mapWords.insert(std::make_pair(iter->second.first, iter->second.second.first));
00291                                                                 mapPoints.insert(std::make_pair(iter->second.first, util3d::transformPoint(iter->second.second.second.first, newFramePose)));
00292                                                                 mapDescriptors.insert(std::make_pair(iter->second.first, iter->second.second.second.second));
00293                                                                 ++added;
00294                                                         }
00295                                                 }
00296 
00297                                                 // remove words in map if max size is reached
00298                                                 if((int)mapPoints.size() > maximumMapSize_)
00299                                                 {
00300                                                         // remove oldest first, keep matched features
00301                                                         std::set<int> matches(regInfo.matchesIDs.begin(), regInfo.matchesIDs.end());
00302                                                         std::multimap<int, cv::Mat>::iterator iterMapDescriptors = mapDescriptors.begin();
00303                                                         std::multimap<int, cv::KeyPoint>::iterator iterMapWords = mapWords.begin();
00304                                                         for(std::multimap<int, cv::Point3f>::iterator iter = mapPoints.begin();
00305                                                                 iter!=mapPoints.end() && (int)mapPoints.size() > maximumMapSize_ && mapPoints.size() >= newIds.size();)
00306                                                         {
00307                                                                 if(matches.find(iter->first) == matches.end())
00308                                                                 {
00309                                                                         mapPoints.erase(iter++);
00310                                                                         mapDescriptors.erase(iterMapDescriptors++);
00311                                                                         mapWords.erase(iterMapWords++);
00312                                                                         ++removed;
00313                                                                 }
00314                                                                 else
00315                                                                 {
00316                                                                         ++iter;
00317                                                                         ++iterMapDescriptors;
00318                                                                         ++iterMapWords;
00319                                                                 }
00320                                                         }
00321                                                 }
00322                                                 modified = true;
00323                                         }
00324 
00325                                         // Geometric
00326                                         UDEBUG("scankeyframeThr=%f icpInliersRatio=%f", scanKeyFrameThr_, regInfo.icpInliersRatio);
00327                                         if(regPipeline_->isScanRequired() &&
00328                                                 (scanKeyFrameThr_==0 || regInfo.icpInliersRatio <= scanKeyFrameThr_))
00329                                         {
00330                                                 UINFO("Update local scan map %d (ratio=%f < %f)", lastFrame_->id(), regInfo.icpInliersRatio, scanKeyFrameThr_);
00331 
00332                                                 UTimer tmpTimer;
00333                                                 if(lastFrame_->sensorData().laserScanRaw().cols)
00334                                                 {
00335                                                         pcl::PointCloud<pcl::PointNormal>::Ptr mapCloudNormals = util3d::laserScanToPointCloudNormal(mapScan);
00336                                                         pcl::PointCloud<pcl::PointNormal>::Ptr frameCloudNormals = util3d::laserScanToPointCloudNormal(lastFrame_->sensorData().laserScanRaw(), newFramePose);
00337 
00338                                                         pcl::IndicesPtr frameCloudNormalsIndices(new std::vector<int>);
00339                                                         int newPoints;
00340                                                         if(mapCloudNormals->size() && scanSubtractRadius_ > 0.0f)
00341                                                         {
00342                                                                 frameCloudNormalsIndices = util3d::subtractFiltering(
00343                                                                                 frameCloudNormals,
00344                                                                                 pcl::IndicesPtr(new std::vector<int>),
00345                                                                                 mapCloudNormals,
00346                                                                                 pcl::IndicesPtr(new std::vector<int>),
00347                                                                                 scanSubtractRadius_,
00348                                                                                 0.0f);
00349                                                                 newPoints = frameCloudNormalsIndices->size();
00350                                                         }
00351                                                         else
00352                                                         {
00353                                                                 newPoints = mapCloudNormals->size();
00354                                                         }
00355 
00356                                                         if(newPoints)
00357                                                         {
00358                                                                 scansBuffer_.push_back(std::make_pair(frameCloudNormals, frameCloudNormalsIndices));
00359 
00360                                                                 //remove points if too big
00361                                                                 UDEBUG("scansBuffer=%d, mapSize=%d newPoints=%d maxPoints=%d",
00362                                                                                 (int)scansBuffer_.size(),
00363                                                                                 int(mapCloudNormals->size()),
00364                                                                                 newPoints,
00365                                                                                 scanMaximumMapSize_);
00366 
00367                                                                 if(newPoints < 20)
00368                                                                 {
00369                                                                         UWARN("The number of new scan points added to local odometry "
00370                                                                                   "map is low (%d), you may want to decrease the parameter \"%s\" "
00371                                                                                   "(current value=%f and ICP inliers ratio is %f)",
00372                                                                                         newPoints,
00373                                                                                         Parameters::kOdomScanKeyFrameThr().c_str(),
00374                                                                                         scanKeyFrameThr_,
00375                                                                                         regInfo.icpInliersRatio);
00376                                                                 }
00377 
00378                                                                 if(scansBuffer_.size() > 1 &&
00379                                                                         int(mapCloudNormals->size() + newPoints) > scanMaximumMapSize_)
00380                                                                 {
00381                                                                         //regenerate the local map
00382                                                                         mapCloudNormals->clear();
00383                                                                         std::list<int> toRemove;
00384                                                                         int i = int(scansBuffer_.size())-1;
00385                                                                         for(; i>=0; --i)
00386                                                                         {
00387                                                                                 int pointsToAdd = scansBuffer_[i].second->size()?scansBuffer_[i].second->size():scansBuffer_[i].first->size();
00388                                                                                 if((int)mapCloudNormals->size() + pointsToAdd > scanMaximumMapSize_ ||
00389                                                                                         i == 0)
00390                                                                                 {
00391                                                                                         *mapCloudNormals += *scansBuffer_[i].first;
00392                                                                                         break;
00393                                                                                 }
00394                                                                                 else
00395                                                                                 {
00396                                                                                         if(scansBuffer_[i].second->size())
00397                                                                                         {
00398                                                                                                 pcl::PointCloud<pcl::PointNormal> tmp;
00399                                                                                                 pcl::copyPointCloud(*scansBuffer_[i].first, *scansBuffer_[i].second, tmp);
00400                                                                                                 *mapCloudNormals += tmp;
00401                                                                                         }
00402                                                                                         else
00403                                                                                         {
00404                                                                                                 *mapCloudNormals += *scansBuffer_[i].first;
00405                                                                                         }
00406                                                                                 }
00407                                                                         }
00408                                                                         // remove old clouds
00409                                                                         if(i > 0)
00410                                                                         {
00411                                                                                 std::vector<std::pair<pcl::PointCloud<pcl::PointNormal>::Ptr, pcl::IndicesPtr> > scansTmp(scansBuffer_.size()-i);
00412                                                                                 int oi = 0;
00413                                                                                 for(; i<(int)scansBuffer_.size(); ++i)
00414                                                                                 {
00415                                                                                         UASSERT(oi < (int)scansTmp.size());
00416                                                                                         scansTmp[oi++] = scansBuffer_[i];
00417                                                                                 }
00418                                                                                 scansBuffer_ = scansTmp;
00419                                                                         }
00420                                                                 }
00421                                                                 else
00422                                                                 {
00423                                                                         // just append the last cloud
00424                                                                         if(scansBuffer_.back().second->size())
00425                                                                         {
00426                                                                                 pcl::PointCloud<pcl::PointNormal> tmp;
00427                                                                                 pcl::copyPointCloud(*scansBuffer_.back().first, *scansBuffer_.back().second, tmp);
00428                                                                                 *mapCloudNormals += tmp;
00429                                                                         }
00430                                                                         else
00431                                                                         {
00432                                                                                 *mapCloudNormals += *scansBuffer_.back().first;
00433                                                                         }
00434                                                                 }
00435                                                                 mapScan = util3d::laserScanFromPointCloud(*mapCloudNormals);
00436                                                                 modified=true;
00437                                                         }
00438                                                 }
00439                                                 UDEBUG("Update local map = %fs", tmpTimer.ticks());
00440                                         }
00441 
00442                                         if(modified)
00443                                         {
00444                                                 *map_ = tmpMap;
00445 
00446                                                 map_->sensorData().setLaserScanRaw(mapScan, 0, 0);
00447                                                 map_->setWords(mapWords);
00448                                                 map_->setWords3(mapPoints);
00449                                                 map_->setWordsDescriptors(mapDescriptors);
00450                                         }
00451                                 }
00452                                 else
00453                                 {
00454                                         // fixed local map, don't update with the new signature
00455                                 }
00456                         }
00457 
00458                         if(info)
00459                         {
00460                                 // use tmpMap instead of map_ to make sure that correspondences with the new frame matches
00461                                 info->localMapSize = (int)tmpMap.getWords3().size();
00462                                 info->localScanMapSize = tmpMap.sensorData().laserScanRaw().cols;
00463                                 if(this->isInfoDataFilled())
00464                                 {
00465                                         info->localMap = uMultimapToMap(tmpMap.getWords3());
00466                                         info->localScanMap = tmpMap.sensorData().laserScanRaw();
00467                                 }
00468                         }
00469                 }
00470                 else
00471                 {
00472                         // just generate keypoints for the new signature
00473                         if(regPipeline_->isImageRequired())
00474                         {
00475                                 Signature dummy;
00476                                 regPipeline_->computeTransformationMod(
00477                                                 *lastFrame_,
00478                                                 dummy);
00479                         }
00480 
00481                         data.setFeatures(lastFrame_->sensorData().keypoints(), lastFrame_->sensorData().descriptors());
00482 
00483                         // a very high variance tells that the new pose is not linked with the previous one
00484                         regInfo.variance = 9999;
00485 
00486                         bool frameValid = false;
00487                         Transform newFramePose = this->getPose(); // initial pose may be not identity...
00488                         if(regPipeline_->isImageRequired())
00489                         {
00490                                 if ((int)lastFrame_->getWords3().size() >= regPipeline_->getMinVisualCorrespondences())
00491                                 {
00492                                         frameValid = true;
00493                                         if (fixedMapPath_.empty())
00494                                         {
00495                                                 // update local map
00496                                                 UASSERT_MSG(lastFrame_->getWordsDescriptors().size() == lastFrame_->getWords3().size(), uFormat("%d vs %d", lastFrame_->getWordsDescriptors().size(), lastFrame_->getWords3().size()).c_str());
00497                                                 UASSERT(lastFrame_->getWords3().size() == lastFrame_->getWords().size());
00498 
00499                                                 std::multimap<int, cv::KeyPoint> words;
00500                                                 std::multimap<int, cv::Point3f> transformedPoints;
00501                                                 std::multimap<int, cv::Mat> descriptors;
00502                                                 UASSERT(lastFrame_->getWords3().size() == lastFrame_->getWordsDescriptors().size());
00503                                                 std::multimap<int, cv::KeyPoint>::const_iterator wordsIter = lastFrame_->getWords().begin();
00504                                                 std::multimap<int, cv::Mat>::const_iterator descIter = lastFrame_->getWordsDescriptors().begin();
00505                                                 for (std::multimap<int, cv::Point3f>::const_iterator iter = lastFrame_->getWords3().begin();
00506                                                         iter != lastFrame_->getWords3().end();
00507                                                         ++iter, ++descIter, ++wordsIter)
00508                                                 {
00509                                                         if (util3d::isFinite(iter->second))
00510                                                         {
00511                                                                 words.insert(*wordsIter);
00512                                                                 transformedPoints.insert(std::make_pair(iter->first, util3d::transformPoint(iter->second, newFramePose)));
00513                                                                 descriptors.insert(*descIter);
00514                                                         }
00515                                                 }
00516                                                 map_->setWords(words);
00517                                                 map_->setWords3(transformedPoints);
00518                                                 map_->setWordsDescriptors(descriptors);
00519 
00520                                                 map_->sensorData().setCameraModels(lastFrame_->sensorData().cameraModels());
00521                                                 map_->sensorData().setStereoCameraModel(lastFrame_->sensorData().stereoCameraModel());
00522                                         }
00523                                 }
00524                                 else
00525                                 {
00526                                         UWARN("%d visual features required to initialize the odometry (only %d extracted).", regPipeline_->getMinVisualCorrespondences(), (int)lastFrame_->getWords3().size());
00527                                 }
00528                         }
00529                         if(regPipeline_->isScanRequired())
00530                         {
00531                                 if (lastFrame_->sensorData().laserScanRaw().cols)
00532                                 {
00533                                         frameValid = true;
00534                                         if (fixedMapPath_.empty())
00535                                         {
00536                                                 pcl::PointCloud<pcl::PointNormal>::Ptr mapCloudNormals = util3d::laserScanToPointCloudNormal(lastFrame_->sensorData().laserScanRaw(), newFramePose);
00537                                                 scansBuffer_.push_back(std::make_pair(mapCloudNormals, pcl::IndicesPtr(new std::vector<int>)));
00538                                                 map_->sensorData().setLaserScanRaw(util3d::laserScanFromPointCloud(*mapCloudNormals), 0,0);
00539                                         }
00540                                 }
00541                                 else
00542                                 {
00543                                         UWARN("Missing scan to initialize odometry.");
00544                                 }
00545                         }
00546 
00547                         if (frameValid)
00548                         {
00549                                 // We initialized the local map
00550                                 output.setIdentity();
00551                         }
00552 
00553                         if(info)
00554                         {
00555                                 info->localMapSize = (int)map_->getWords3().size();
00556                                 info->localScanMapSize = map_->sensorData().laserScanRaw().cols;
00557 
00558                                 if(this->isInfoDataFilled())
00559                                 {
00560                                         info->localMap = uMultimapToMap(map_->getWords3());
00561                                         info->localScanMap = map_->sensorData().laserScanRaw();
00562                                 }
00563                         }
00564                 }
00565 
00566                 map_->sensorData().setFeatures(std::vector<cv::KeyPoint>(), cv::Mat()); // clear sensorData features
00567 
00568                 nFeatures = lastFrame_->getWords().size();
00569                 if(this->isInfoDataFilled() && info)
00570                 {
00571                         if(regPipeline_->isImageRequired())
00572                         {
00573                                 info->words = lastFrame_->getWords();
00574                         }
00575                 }
00576         }
00577 
00578         if(info)
00579         {
00580                 info->variance = regInfo.variance;
00581                 info->inliers = regInfo.inliers;
00582                 info->matches = regInfo.matches;
00583                 info->icpInliersRatio = regInfo.icpInliersRatio;
00584                 info->features = nFeatures;
00585 
00586                 if(this->isInfoDataFilled())
00587                 {
00588                         info->wordMatches = regInfo.matchesIDs;
00589                         info->wordInliers = regInfo.inliersIDs;
00590                 }
00591         }
00592 
00593         UINFO("Odom update time = %fs lost=%s features=%d inliers=%d/%d variance=%f local_map=%d local_scan_map=%d",
00594                         timer.elapsed(),
00595                         output.isNull()?"true":"false",
00596                         nFeatures,
00597                         regInfo.inliers,
00598                         regInfo.matches,
00599                         regInfo.variance,
00600                         regPipeline_->isImageRequired()?(int)map_->getWords3().size():0,
00601                         regPipeline_->isScanRequired()?(int)map_->sensorData().laserScanRaw().cols:0);
00602         return output;
00603 }
00604 
00605 } // namespace rtabmap


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