BayesFilter.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/BayesFilter.h"
00029 #include "rtabmap/core/Memory.h"
00030 #include "rtabmap/core/Signature.h"
00031 #include "rtabmap/core/Parameters.h"
00032 #include <iostream>
00033 #include <set>
00034 #if __cplusplus >= 201103L
00035 #include <unordered_map>
00036 #include <unordered_set>
00037 #endif
00038 
00039 #include "rtabmap/utilite/UtiLite.h"
00040 
00041 namespace rtabmap {
00042 
00043 BayesFilter::BayesFilter(const ParametersMap & parameters) :
00044         _virtualPlacePrior(Parameters::defaultBayesVirtualPlacePriorThr()),
00045         _fullPredictionUpdate(Parameters::defaultBayesFullPredictionUpdate()),
00046         _totalPredictionLCValues(0.0f)
00047 {
00048         this->setPredictionLC(Parameters::defaultBayesPredictionLC());
00049         this->parseParameters(parameters);
00050 }
00051 
00052 BayesFilter::~BayesFilter() {
00053 }
00054 
00055 void BayesFilter::parseParameters(const ParametersMap & parameters)
00056 {
00057         ParametersMap::const_iterator iter;
00058         if((iter=parameters.find(Parameters::kBayesPredictionLC())) != parameters.end())
00059         {
00060                 this->setPredictionLC((*iter).second);
00061         }
00062         Parameters::parse(parameters, Parameters::kBayesVirtualPlacePriorThr(), _virtualPlacePrior);
00063         Parameters::parse(parameters, Parameters::kBayesFullPredictionUpdate(), _fullPredictionUpdate);
00064 
00065         UASSERT(_virtualPlacePrior >= 0 && _virtualPlacePrior <= 1.0f);
00066 }
00067 
00068 // format = {Virtual place, Loop closure, level1, level2, l3, l4...}
00069 void BayesFilter::setPredictionLC(const std::string & prediction)
00070 {
00071         std::list<std::string> strValues = uSplit(prediction, ' ');
00072         if(strValues.size() < 2)
00073         {
00074                 UERROR("The number of values < 2 (prediction=\"%s\")", prediction.c_str());
00075         }
00076         else
00077         {
00078                 std::vector<double> tmpValues(strValues.size());
00079                 int i=0;
00080                 bool valid = true;
00081                 for(std::list<std::string>::iterator iter = strValues.begin(); iter!=strValues.end(); ++iter)
00082                 {
00083                         tmpValues[i] = uStr2Float((*iter).c_str());
00084                         //UINFO("%d=%e", i, tmpValues[i]);
00085                         if(tmpValues[i] < 0.0 || tmpValues[i]>1.0)
00086                         {
00087                                 valid = false;
00088                                 break;
00089                         }
00090                         ++i;
00091                 }
00092 
00093                 if(!valid)
00094                 {
00095                         UERROR("The prediction is not valid (values must be between >0 && <=1) prediction=\"%s\"", prediction.c_str());
00096                 }
00097                 else
00098                 {
00099                         _predictionLC = tmpValues;
00100                 }
00101         }
00102         _totalPredictionLCValues = 0.0f;
00103         for(unsigned int j=0; j<_predictionLC.size(); ++j)
00104         {
00105                 _totalPredictionLCValues += _predictionLC[j];
00106         }
00107 }
00108 
00109 const std::vector<double> & BayesFilter::getPredictionLC() const
00110 {
00111         // {Vp, Lc, l1, l2, l3, l4...}
00112         return _predictionLC;
00113 }
00114 
00115 std::string BayesFilter::getPredictionLCStr() const
00116 {
00117         std::string values;
00118         for(unsigned int i=0; i<_predictionLC.size(); ++i)
00119         {
00120                 values.append(uNumber2Str(_predictionLC[i]));
00121                 if(i+1 < _predictionLC.size())
00122                 {
00123                         values.append(" ");
00124                 }
00125         }
00126         return values;
00127 }
00128 
00129 void BayesFilter::reset()
00130 {
00131         _posterior.clear();
00132         _prediction = cv::Mat();
00133         _neighborsIndex.clear();
00134 }
00135 
00136 const std::map<int, float> & BayesFilter::computePosterior(const Memory * memory, const std::map<int, float> & likelihood)
00137 {
00138         ULOGGER_DEBUG("");
00139 
00140         if(!memory)
00141         {
00142                 ULOGGER_ERROR("Memory is Null!");
00143                 return _posterior;
00144         }
00145 
00146         if(!likelihood.size())
00147         {
00148                 ULOGGER_ERROR("likelihood is empty!");
00149                 return _posterior;
00150         }
00151 
00152         if(_predictionLC.size() < 2)
00153         {
00154                 ULOGGER_ERROR("Prediction is not valid!");
00155                 return _posterior;
00156         }
00157 
00158         UTimer timer;
00159         timer.start();
00160 
00161         cv::Mat prior;
00162         cv::Mat posterior;
00163 
00164         float sum = 0;
00165         int j=0;
00166         // Recursive Bayes estimation...
00167         // STEP 1 - Prediction : Prior*lastPosterior
00168         _prediction = this->generatePrediction(memory, uKeys(likelihood));
00169 
00170         UDEBUG("STEP1-generate prior=%fs, rows=%d, cols=%d", timer.ticks(), _prediction.rows, _prediction.cols);
00171         //std::cout << "Prediction=" << _prediction << std::endl;
00172 
00173         // Adjust the last posterior if some images were
00174         // reactivated or removed from the working memory
00175         posterior = cv::Mat(likelihood.size(), 1, CV_32FC1);
00176         this->updatePosterior(memory, uKeys(likelihood));
00177         j=0;
00178         for(std::map<int, float>::const_iterator i=_posterior.begin(); i!= _posterior.end(); ++i)
00179         {
00180                 ((float*)posterior.data)[j++] = (*i).second;
00181         }
00182         ULOGGER_DEBUG("STEP1-update posterior=%fs, posterior=%d, _posterior size=%d", posterior.rows, _posterior.size());
00183         //std::cout << "LastPosterior=" << posterior << std::endl;
00184 
00185         // Multiply prediction matrix with the last posterior
00186         // (m,m) X (m,1) = (m,1)
00187         prior = _prediction * posterior;
00188         ULOGGER_DEBUG("STEP1-matrix mult time=%fs", timer.ticks());
00189         //std::cout << "ResultingPrior=" << prior << std::endl;
00190 
00191         ULOGGER_DEBUG("STEP1-matrix mult time=%fs", timer.ticks());
00192         std::vector<float> likelihoodValues = uValues(likelihood);
00193         //std::cout << "Likelihood=" << cv::Mat(likelihoodValues) << std::endl;
00194 
00195         // STEP 2 - Update : Multiply with observations (likelihood)
00196         j=0;
00197         for(std::map<int, float>::const_iterator i=likelihood.begin(); i!= likelihood.end(); ++i)
00198         {
00199                 std::map<int, float>::iterator p =_posterior.find((*i).first);
00200                 if(p!= _posterior.end())
00201                 {
00202                         (*p).second = (*i).second * ((float*)prior.data)[j++];
00203                         sum+=(*p).second;
00204                 }
00205                 else
00206                 {
00207                         ULOGGER_ERROR("Problem1! can't find id=%d", (*i).first);
00208                 }
00209         }
00210         ULOGGER_DEBUG("STEP2-likelihood time=%fs", timer.ticks());
00211         //std::cout << "Posterior (before normalization)=" << _posterior << std::endl;
00212 
00213         // Normalize
00214         ULOGGER_DEBUG("sum=%f", sum);
00215         if(sum != 0)
00216         {
00217                 for(std::map<int, float>::iterator i=_posterior.begin(); i!= _posterior.end(); ++i)
00218                 {
00219                         (*i).second /= sum;
00220                 }
00221         }
00222         ULOGGER_DEBUG("normalize time=%fs", timer.ticks());
00223         //std::cout << "Posterior=" << _posterior << std::endl;
00224 
00225         return _posterior;
00226 }
00227 
00228 float addNeighborProb(cv::Mat & prediction,
00229                         unsigned int col,
00230                         const std::map<int, int> & neighbors,
00231                         const std::vector<double> & predictionLC,
00232 #if __cplusplus >= 201103L
00233                         const std::unordered_map<int, int> & idToIndex
00234 #else
00235                         const std::map<int, int> & idToIndex
00236 #endif
00237                         )
00238 {
00239         UASSERT(col < (unsigned int)prediction.cols &&
00240                         col < (unsigned int)prediction.rows);
00241 
00242         float sum=0.0f;
00243         float * dataPtr = (float*)prediction.data;
00244         for(std::map<int, int>::const_iterator iter=neighbors.begin(); iter!=neighbors.end(); ++iter)
00245         {
00246                 if(iter->first>=0)
00247                 {
00248 #if __cplusplus >= 201103L
00249                         std::unordered_map<int, int>::const_iterator jter = idToIndex.find(iter->first);
00250 #else
00251                         std::map<int, int>::const_iterator jter = idToIndex.find(iter->first);
00252 #endif
00253                         if(jter != idToIndex.end())
00254                         {
00255                                 UASSERT((iter->second+1) < (int)predictionLC.size());
00256                                 sum += dataPtr[col + jter->second*prediction.cols] = predictionLC[iter->second+1];
00257                         }
00258                 }
00259         }
00260         return sum;
00261 }
00262 
00263 
00264 cv::Mat BayesFilter::generatePrediction(const Memory * memory, const std::vector<int> & ids)
00265 {
00266         if(!_fullPredictionUpdate && !_prediction.empty())
00267         {
00268                 return updatePrediction(_prediction, memory, uKeys(_posterior), ids);
00269         }
00270         UDEBUG("");
00271 
00272         UASSERT(memory &&
00273                    _predictionLC.size() >= 2 &&
00274                    ids.size());
00275 
00276         UTimer timer;
00277         timer.start();
00278         UTimer timerGlobal;
00279         timerGlobal.start();
00280 
00281 #if __cplusplus >= 201103L
00282         std::unordered_map<int,int> idToIndexMap;
00283         idToIndexMap.reserve(ids.size());
00284 #else
00285         std::map<int,int> idToIndexMap;
00286 #endif
00287         for(unsigned int i=0; i<ids.size(); ++i)
00288         {
00289                 if(ids[i]>0)
00290                 {
00291                         idToIndexMap[ids[i]] = i;
00292                 }
00293         }
00294 
00295 
00296         //int rows = prediction.rows;
00297         cv::Mat prediction = cv::Mat::zeros(ids.size(), ids.size(), CV_32FC1);
00298         int cols = prediction.cols;
00299 
00300         // Each prior is a column vector
00301         UDEBUG("_predictionLC.size()=%d",_predictionLC.size());
00302         std::set<int> idsDone;
00303 
00304         for(unsigned int i=0; i<ids.size(); ++i)
00305         {
00306                 if(idsDone.find(ids[i]) == idsDone.end())
00307                 {
00308                         if(ids[i] > 0)
00309                         {
00310                                 // Set high values (gaussians curves) to loop closure neighbors
00311 
00312                                 // ADD prob for each neighbors
00313                                 std::map<int, int> neighbors = memory->getNeighborsId(ids[i], _predictionLC.size()-1, 0, false, false, true, true);
00314 
00315                                 if(!_fullPredictionUpdate)
00316                                 {
00317                                         uInsert(_neighborsIndex, std::make_pair(ids[i], neighbors));
00318                                 }
00319 
00320                                 std::list<int> idsLoopMargin;
00321                                 //filter neighbors in STM
00322                                 for(std::map<int, int>::iterator iter=neighbors.begin(); iter!=neighbors.end();)
00323                                 {
00324                                         if(memory->isInSTM(iter->first))
00325                                         {
00326                                                 neighbors.erase(iter++);
00327                                         }
00328                                         else
00329                                         {
00330                                                 if(iter->second == 0 && idToIndexMap.find(iter->first)!=idToIndexMap.end())
00331                                                 {
00332                                                         idsLoopMargin.push_back(iter->first);
00333                                                 }
00334                                                 ++iter;
00335                                         }
00336                                 }
00337 
00338                                 // should at least have 1 id in idsMarginLoop
00339                                 if(idsLoopMargin.size() == 0)
00340                                 {
00341                                         UFATAL("No 0 margin neighbor for signature %d !?!?", ids[i]);
00342                                 }
00343 
00344                                 // same neighbor tree for loop signatures (margin = 0)
00345                                 for(std::list<int>::iterator iter = idsLoopMargin.begin(); iter!=idsLoopMargin.end(); ++iter)
00346                                 {
00347                                         if(!_fullPredictionUpdate)
00348                                         {
00349                                                 uInsert(_neighborsIndex, std::make_pair(*iter, neighbors));
00350                                         }
00351 
00352                                         float sum = 0.0f; // sum values added
00353                                         int index = idToIndexMap.at(*iter);
00354                                         sum += addNeighborProb(prediction, index, neighbors, _predictionLC, idToIndexMap);
00355                                         idsDone.insert(*iter);
00356                                         this->normalize(prediction, index, sum, ids[0]<0);
00357                                 }
00358                         }
00359                         else
00360                         {
00361                                 // Set the virtual place prior
00362                                 if(_virtualPlacePrior > 0)
00363                                 {
00364                                         if(cols>1) // The first must be the virtual place
00365                                         {
00366                                                 ((float*)prediction.data)[i] = _virtualPlacePrior;
00367                                                 float val = (1.0-_virtualPlacePrior)/(cols-1);
00368                                                 for(int j=1; j<cols; j++)
00369                                                 {
00370                                                         ((float*)prediction.data)[i + j*cols] = val;
00371                                                 }
00372                                         }
00373                                         else if(cols>0)
00374                                         {
00375                                                 ((float*)prediction.data)[i] = 1;
00376                                         }
00377                                 }
00378                                 else
00379                                 {
00380                                         // Only for some tests...
00381                                         // when _virtualPlacePrior=0, set all priors to the same value
00382                                         if(cols>1)
00383                                         {
00384                                                 float val = 1.0/cols;
00385                                                 for(int j=0; j<cols; j++)
00386                                                 {
00387                                                         ((float*)prediction.data)[i + j*cols] = val;
00388                                                 }
00389                                         }
00390                                         else if(cols>0)
00391                                         {
00392                                                 ((float*)prediction.data)[i] = 1;
00393                                         }
00394                                 }
00395                         }
00396                 }
00397         }
00398 
00399         ULOGGER_DEBUG("time = %fs", timerGlobal.ticks());
00400 
00401         return prediction;
00402 }
00403 
00404 void BayesFilter::normalize(cv::Mat & prediction, unsigned int index, float addedProbabilitiesSum, bool virtualPlaceUsed) const
00405 {
00406         UASSERT(index < (unsigned int)prediction.rows && index < (unsigned int)prediction.cols);
00407 
00408         int cols = prediction.cols;
00409         // ADD values of not found neighbors to loop closure
00410         if(addedProbabilitiesSum < _totalPredictionLCValues-_predictionLC[0])
00411         {
00412                 float delta = _totalPredictionLCValues-_predictionLC[0]-addedProbabilitiesSum;
00413                 ((float*)prediction.data)[index + index*cols] += delta;
00414                 addedProbabilitiesSum+=delta;
00415         }
00416 
00417         float allOtherPlacesValue = 0;
00418         if(_totalPredictionLCValues < 1)
00419         {
00420                 allOtherPlacesValue = 1.0f - _totalPredictionLCValues;
00421         }
00422 
00423         // Set all loop events to small values according to the model
00424         if(allOtherPlacesValue > 0 && cols>1)
00425         {
00426                 float value = allOtherPlacesValue / float(cols - 1);
00427                 for(int j=virtualPlaceUsed?1:0; j<cols; ++j)
00428                 {
00429                         if(((float*)prediction.data)[index + j*cols] == 0)
00430                         {
00431                                 ((float*)prediction.data)[index + j*cols] = value;
00432                                 addedProbabilitiesSum += ((float*)prediction.data)[index + j*cols];
00433                         }
00434                 }
00435         }
00436 
00437         //normalize this row
00438         float maxNorm = 1 - (virtualPlaceUsed?_predictionLC[0]:0); // 1 - virtual place probability
00439         if(addedProbabilitiesSum<maxNorm-0.0001 || addedProbabilitiesSum>maxNorm+0.0001)
00440         {
00441                 for(int j=virtualPlaceUsed?1:0; j<cols; ++j)
00442                 {
00443                         ((float*)prediction.data)[index + j*cols] *= maxNorm / addedProbabilitiesSum;
00444                 }
00445                 addedProbabilitiesSum = maxNorm;
00446         }
00447 
00448         // ADD virtual place prob
00449         if(virtualPlaceUsed)
00450         {
00451                 ((float*)prediction.data)[index] = _predictionLC[0];
00452                 addedProbabilitiesSum += ((float*)prediction.data)[index];
00453         }
00454 
00455         //debug
00456         //for(int j=0; j<cols; ++j)
00457         //{
00458         //      ULOGGER_DEBUG("test col=%d = %f", i, prediction.data.fl[i + j*cols]);
00459         //}
00460 
00461         if(addedProbabilitiesSum<0.99 || addedProbabilitiesSum > 1.01)
00462         {
00463                 UWARN("Prediction is not normalized sum=%f", addedProbabilitiesSum);
00464         }
00465 }
00466 
00467 cv::Mat BayesFilter::updatePrediction(const cv::Mat & oldPrediction,
00468                 const Memory * memory,
00469                 const std::vector<int> & oldIds,
00470                 const std::vector<int> & newIds)
00471 {
00472         UTimer timer;
00473         UDEBUG("");
00474 
00475         UASSERT(memory &&
00476                 oldIds.size() &&
00477                 newIds.size() &&
00478                 oldIds.size() == (unsigned int)oldPrediction.cols &&
00479                 oldIds.size() == (unsigned int)oldPrediction.rows);
00480 
00481         cv::Mat prediction = cv::Mat::zeros(newIds.size(), newIds.size(), CV_32FC1);
00482         UDEBUG("time creating prediction = %fs", timer.restart());
00483 
00484         // Create id to index maps
00485 #if __cplusplus >= 201103L
00486         std::unordered_set<int> oldIdsSet(oldIds.begin(), oldIds.end());
00487 #else
00488         std::set<int> oldIdsSet(oldIds.begin(), oldIds.end());
00489 #endif
00490         UDEBUG("time creating old ids set = %fs", timer.restart());
00491 
00492 #if __cplusplus >= 201103L
00493         std::unordered_map<int,int> newIdToIndexMap;
00494         newIdToIndexMap.reserve(newIds.size());
00495 #else
00496         std::map<int,int> newIdToIndexMap;
00497 #endif
00498         for(unsigned int i=0; i<newIds.size(); ++i)
00499         {
00500                 if(newIds[i]>0)
00501                 {
00502                         newIdToIndexMap[newIds[i]] = i;
00503                 }
00504         }
00505 
00506         UDEBUG("time creating id-index vector (size=%d oldIds.back()=%d newIds.back()=%d) = %fs", (int)newIdToIndexMap.size(), oldIds.back(), newIds.back(), timer.restart());
00507 
00508         //Get removed ids
00509         std::set<int> removedIds;
00510         for(unsigned int i=0; i<oldIds.size(); ++i)
00511         {
00512                 if(oldIds[i] > 0 && newIdToIndexMap.find(oldIds[i]) == newIdToIndexMap.end())
00513                 {
00514                         removedIds.insert(removedIds.end(), oldIds[i]);
00515                         _neighborsIndex.erase(oldIds[i]);
00516                         UDEBUG("removed id=%d at oldIndex=%d", oldIds[i], i);
00517                 }
00518         }
00519         UDEBUG("time getting removed ids = %fs", timer.restart());
00520 
00521         int added = 0;
00522         float epsilon = 0.00001f;
00523         // get ids to update
00524         std::set<int> idsToUpdate;
00525         for(unsigned int i=0; i<oldIds.size() || i<newIds.size(); ++i)
00526         {
00527                 if(i<oldIds.size())
00528                 {
00529                         if(removedIds.find(oldIds[i]) != removedIds.end())
00530                         {
00531                                 unsigned int cols = oldPrediction.cols;
00532                                 int count = 0;
00533                                 for(unsigned int j=0; j<cols; ++j)
00534                                 {
00535                                         if(((const float *)oldPrediction.data)[i + j*cols] > epsilon &&
00536                                            j!=i &&
00537                                            removedIds.find(oldIds[j]) == removedIds.end())
00538                                         {
00539                                                 //UDEBUG("to update id=%d from id=%d removed (value=%f)", oldIds[j], oldIds[i], ((const float *)oldPrediction.data)[i + j*cols]);
00540                                                 idsToUpdate.insert(oldIds[j]);
00541                                                 ++count;
00542                                         }
00543                                 }
00544                                 UDEBUG("From removed id %d, %d neighbors to update.", oldIds[i], count);
00545                         }
00546                 }
00547                 if(i<newIds.size() && oldIdsSet.find(newIds[i]) == oldIdsSet.end())
00548                 {
00549                         if(_neighborsIndex.find(newIds[i]) == _neighborsIndex.end())
00550                         {
00551                                 std::map<int, int> neighbors = memory->getNeighborsId(newIds[i], _predictionLC.size()-1, 0, false, false, true, true);
00552 
00553                                 for(std::map<int, int>::iterator iter=neighbors.begin(); iter!=neighbors.end(); ++iter)
00554                                 {
00555                                         std::map<int, std::map<int, int> >::iterator jter = _neighborsIndex.find(iter->first);
00556                                         if(jter != _neighborsIndex.end())
00557                                         {
00558                                                 uInsert(jter->second, std::make_pair(newIds[i], iter->second));
00559                                         }
00560                                 }
00561                                 _neighborsIndex.insert(std::make_pair(newIds[i], neighbors));
00562                         }
00563                         const std::map<int, int> & neighbors = _neighborsIndex.at(newIds[i]);
00564                         //std::map<int, int> neighbors = memory->getNeighborsId(newIds[i], _predictionLC.size()-1, 0, false, false, true, true);
00565 
00566                         float sum = addNeighborProb(prediction, i, neighbors, _predictionLC, newIdToIndexMap);
00567                         this->normalize(prediction, i, sum, newIds[0]<0);
00568                         ++added;
00569                         int count = 0;
00570                         for(std::map<int,int>::const_iterator iter=neighbors.begin(); iter!=neighbors.end(); ++iter)
00571                         {
00572                                 if(oldIdsSet.find(iter->first)!=oldIdsSet.end() &&
00573                                    removedIds.find(iter->first) == removedIds.end())
00574                                 {
00575                                         idsToUpdate.insert(iter->first);
00576                                         ++count;
00577                                 }
00578                         }
00579                         UDEBUG("From added id %d, %d neighbors to update.", newIds[i], count);
00580                 }
00581         }
00582         UDEBUG("time getting %d ids to update = %fs", idsToUpdate.size(), timer.restart());
00583 
00584         UTimer t1;
00585         double e0=0,e1=0, e2=0, e3=0, e4=0;
00586         // update modified/added ids
00587         int modified = 0;
00588         for(std::set<int>::iterator iter = idsToUpdate.begin(); iter!=idsToUpdate.end(); ++iter)
00589         {
00590                 int id = *iter;
00591                 if(id > 0)
00592                 {
00593                         int index = newIdToIndexMap.at(id);
00594 
00595                         e0 = t1.ticks();
00596                         std::map<int, std::map<int, int> >::iterator kter = _neighborsIndex.find(id);
00597                         UASSERT_MSG(kter != _neighborsIndex.end(), uFormat("Did not find %d (current index size=%d)", id, (int)_neighborsIndex.size()).c_str());
00598                         const std::map<int, int> & neighbors = kter->second;
00599                         //std::map<int, int> neighbors = memory->getNeighborsId(id, _predictionLC.size()-1, 0, false, false, true, true);
00600                         e1+=t1.ticks();
00601 
00602                         float sum = addNeighborProb(prediction, index, neighbors, _predictionLC, newIdToIndexMap);
00603                         e3+=t1.ticks();
00604 
00605                         this->normalize(prediction, index, sum, newIds[0]<0);
00606                         ++modified;
00607                         e4+=t1.ticks();
00608                 }
00609         }
00610         UDEBUG("time updating modified/added %d ids = %fs (e0=%f e1=%f e2=%f e3=%f e4=%f)", idsToUpdate.size(), timer.restart(), e0, e1, e2, e3, e4);
00611 
00612         //UDEBUG("oldIds.size()=%d, oldPrediction.cols=%d, oldPrediction.rows=%d", oldIds.size(), oldPrediction.cols, oldPrediction.rows);
00613         //UDEBUG("newIdToIndexMap.size()=%d, prediction.cols=%d, prediction.rows=%d", newIdToIndexMap.size(), prediction.cols, prediction.rows);
00614         // copy not changed probabilities
00615         int copied = 0;
00616         for(unsigned int i=0; i<oldIds.size(); ++i)
00617         {
00618                 if(oldIds[i]>0 && removedIds.find(oldIds[i]) == removedIds.end() && idsToUpdate.find(oldIds[i]) == idsToUpdate.end())
00619                 {
00620                         for(int j=i; j<oldPrediction.cols; ++j)
00621                         {
00622                                 if(removedIds.find(oldIds[j]) == removedIds.end() && ((const float *)oldPrediction.data)[i + j*oldPrediction.cols] > epsilon)
00623                                 {
00624                                         //UDEBUG("i=%d, j=%d", i, j);
00625                                         //UDEBUG("oldIds[i]=%d, oldIds[j]=%d", oldIds[i], oldIds[j]);
00626                                         //UDEBUG("newIdToIndexMap.at(oldIds[i])=%d", newIdToIndexMap.at(oldIds[i]));
00627                                         //UDEBUG("newIdToIndexMap.at(oldIds[j])=%d", newIdToIndexMap.at(oldIds[j]));
00628                                         float v = ((const float *)oldPrediction.data)[i + j*oldPrediction.cols];
00629                                         int ii = newIdToIndexMap.at(oldIds[i]);
00630                                         int jj = newIdToIndexMap.at(oldIds[j]);
00631                                         ((float *)prediction.data)[ii + jj*prediction.cols] = v;
00632                                         if(ii != jj)
00633                                         {
00634                                                 ((float *)prediction.data)[jj + ii*prediction.cols] = v;
00635                                         }
00636                                 }
00637                         }
00638                         ++copied;
00639                 }
00640         }
00641         UDEBUG("time copying = %fs", timer.restart());
00642 
00643         //update virtual place
00644         if(newIds[0] < 0)
00645         {
00646                 if(prediction.cols>1) // The first must be the virtual place
00647                 {
00648                         ((float*)prediction.data)[0] = _virtualPlacePrior;
00649                         float val = (1.0-_virtualPlacePrior)/(prediction.cols-1);
00650                         for(int j=1; j<prediction.cols; j++)
00651                         {
00652                                 ((float*)prediction.data)[j*prediction.cols] = val;
00653                                 ((float*)prediction.data)[j] = _predictionLC[0];
00654                         }
00655                 }
00656                 else if(prediction.cols>0)
00657                 {
00658                         ((float*)prediction.data)[0] = 1;
00659                 }
00660         }
00661         UDEBUG("time updating virtual place = %fs", timer.restart());
00662 
00663         UDEBUG("Modified=%d, Added=%d, Copied=%d", modified, added, copied);
00664         return prediction;
00665 }
00666 
00667 void BayesFilter::updatePosterior(const Memory * memory, const std::vector<int> & likelihoodIds)
00668 {
00669         ULOGGER_DEBUG("");
00670         std::map<int, float> newPosterior;
00671         for(std::vector<int>::const_iterator i=likelihoodIds.begin(); i != likelihoodIds.end(); ++i)
00672         {
00673                 std::map<int, float>::iterator post = _posterior.find(*i);
00674                 if(post == _posterior.end())
00675                 {
00676                         if(_posterior.size() == 0)
00677                         {
00678                                 newPosterior.insert(std::pair<int, float>(*i, 1));
00679                         }
00680                         else
00681                         {
00682                                 newPosterior.insert(std::pair<int, float>(*i, 0));
00683                         }
00684                 }
00685                 else
00686                 {
00687                         newPosterior.insert(std::pair<int, float>((*post).first, (*post).second));
00688                 }
00689         }
00690         _posterior = newPosterior;
00691 }
00692 
00693 } // namespace rtabmap


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