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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:31