-
Notifications
You must be signed in to change notification settings - Fork 907
Expand file tree
/
Copy pathMemory.cpp
More file actions
6886 lines (6401 loc) · 231 KB
/
Memory.cpp
File metadata and controls
6886 lines (6401 loc) · 231 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the Universite de Sherbrooke nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <rtabmap/utilite/UEventsManager.h>
#include <rtabmap/utilite/ULogger.h>
#include <rtabmap/utilite/UTimer.h>
#include <rtabmap/utilite/UConversion.h>
#include <rtabmap/utilite/UProcessInfo.h>
#include <rtabmap/utilite/UMath.h>
#include "rtabmap/core/Memory.h"
#include "rtabmap/core/Signature.h"
#include "rtabmap/core/Parameters.h"
#include "rtabmap/core/RtabmapEvent.h"
#include "rtabmap/core/VWDictionary.h"
#include <rtabmap/core/EpipolarGeometry.h>
#include "rtabmap/core/VisualWord.h"
#include "rtabmap/core/Features2d.h"
#include "rtabmap/core/GlobalDescriptorExtractor.h"
#include "rtabmap/core/RegistrationIcp.h"
#include "rtabmap/core/Registration.h"
#include "rtabmap/core/RegistrationVis.h"
#include "rtabmap/core/DBDriver.h"
#include "rtabmap/core/util3d_features.h"
#include "rtabmap/core/util3d_filtering.h"
#include "rtabmap/core/util3d_correspondences.h"
#include "rtabmap/core/util3d_registration.h"
#include "rtabmap/core/util3d_surface.h"
#include "rtabmap/core/util3d_transforms.h"
#include "rtabmap/core/util3d_motion_estimation.h"
#include "rtabmap/core/util3d.h"
#include "rtabmap/core/util2d.h"
#include "rtabmap/core/Statistics.h"
#include "rtabmap/core/Compression.h"
#include "rtabmap/core/Graph.h"
#include "rtabmap/core/Stereo.h"
#include "rtabmap/core/optimizer/OptimizerG2O.h"
#include <pcl/io/pcd_io.h>
#include <pcl/common/common.h>
#include <rtabmap/core/MarkerDetector.h>
#include <opencv2/imgproc/types_c.h>
#include <rtabmap/core/LocalGridMaker.h>
namespace rtabmap {
const int Memory::kIdStart = 0;
const int Memory::kIdVirtual = -1;
const int Memory::kIdInvalid = 0;
Memory::Memory(const ParametersMap & parameters) :
_dbDriver(0),
_similarityThreshold(Parameters::defaultMemRehearsalSimilarity()),
_binDataKept(Parameters::defaultMemBinDataKept()),
_rawDescriptorsKept(Parameters::defaultMemRawDescriptorsKept()),
_loadVisualLocalFeaturesOnInit(Parameters::defaultMemLoadVisualLocalFeaturesOnInit()),
_saveDepth16Format(Parameters::defaultMemSaveDepth16Format()),
_notLinkedNodesKeptInDb(Parameters::defaultMemNotLinkedNodesKept()),
_saveIntermediateNodeData(Parameters::defaultMemIntermediateNodeDataKept()),
_rgbCompressionFormat(Parameters::defaultMemImageCompressionFormat()),
_depthCompressionFormat(Parameters::defaultMemDepthCompressionFormat()),
_incrementalMemory(Parameters::defaultMemIncrementalMemory()),
_localizationReadOnly(Parameters::defaultMemLocalizationReadOnly()),
_localizationDataSaved(Parameters::defaultMemLocalizationDataSaved()),
_flannIndexSaved(Parameters::defaultKpFlannIndexSaved()),
_reduceGraph(Parameters::defaultMemReduceGraph()),
_maxStMemSize(Parameters::defaultMemSTMSize()),
_recentWmRatio(Parameters::defaultMemRecentWmRatio()),
_transferSortingByWeightId(Parameters::defaultMemTransferSortingByWeightId()),
_idUpdatedToNewOneRehearsal(Parameters::defaultMemRehearsalIdUpdatedToNewOne()),
_generateIds(Parameters::defaultMemGenerateIds()),
_badSignaturesIgnored(Parameters::defaultMemBadSignaturesIgnored()),
_mapLabelsAdded(Parameters::defaultMemMapLabelsAdded()),
_depthAsMask(Parameters::defaultMemDepthAsMask()),
_maskFloorThreshold(Parameters::defaultMemDepthMaskFloorThr()),
_stereoFromMotion(Parameters::defaultMemStereoFromMotion()),
_imagePreDecimation(Parameters::defaultMemImagePreDecimation()),
_imagePostDecimation(Parameters::defaultMemImagePostDecimation()),
_compressionParallelized(Parameters::defaultMemCompressionParallelized()),
_laserScanDownsampleStepSize(Parameters::defaultMemLaserScanDownsampleStepSize()),
_laserScanVoxelSize(Parameters::defaultMemLaserScanVoxelSize()),
_laserScanNormalK(Parameters::defaultMemLaserScanNormalK()),
_laserScanNormalRadius(Parameters::defaultMemLaserScanNormalRadius()),
_laserScanGroundNormalsUp(Parameters::defaultIcpPointToPlaneGroundNormalsUp()),
_reextractLoopClosureFeatures(Parameters::defaultRGBDLoopClosureReextractFeatures()),
_localBundleOnLoopClosure(Parameters::defaultRGBDLocalBundleOnLoopClosure()),
_invertedReg(Parameters::defaultRGBDInvertedReg()),
_rehearsalMaxDistance(Parameters::defaultRGBDLinearUpdate()),
_rehearsalMaxAngle(Parameters::defaultRGBDAngularUpdate()),
_rehearsalWeightIgnoredWhileMoving(Parameters::defaultMemRehearsalWeightIgnoredWhileMoving()),
_useOdometryFeatures(Parameters::defaultMemUseOdomFeatures()),
_useOdometryGravity(Parameters::defaultMemUseOdomGravity()),
_rotateImagesUpsideUp(Parameters::defaultMemRotateImagesUpsideUp()),
_createOccupancyGrid(Parameters::defaultRGBDCreateOccupancyGrid()),
_visMaxFeatures(Parameters::defaultVisMaxFeatures()),
_visSSC(Parameters::defaultVisSSC()),
_imagesAlreadyRectified(Parameters::defaultRtabmapImagesAlreadyRectified()),
_rectifyOnlyFeatures(Parameters::defaultRtabmapRectifyOnlyFeatures()),
_covOffDiagonalIgnored(Parameters::defaultMemCovOffDiagIgnored()),
_detectMarkers(Parameters::defaultRGBDMarkerDetection()),
_markerLinVariance(Parameters::defaultMarkerVarianceLinear()),
_markerAngVariance(Parameters::defaultMarkerVarianceAngular()),
_markerOrientationIgnored(Parameters::defaultMarkerVarianceOrientationIgnored()),
_idCount(kIdStart),
_idMapCount(kIdStart),
_lastSignature(0),
_lastGlobalLoopClosureId(0),
_memoryChanged(false),
_linksChanged(false),
_signaturesAdded(0),
_allNodesInWM(true),
_receivingOdometryFeatures(false),
_badSignRatio(Parameters::defaultKpBadSignRatio()),
_tfIdfLikelihoodUsed(Parameters::defaultKpTfIdfLikelihoodUsed()),
_parallelized(Parameters::defaultKpParallelized()),
_registrationVis(0)
{
_feature2D = Feature2D::create(parameters);
_vwd = new VWDictionary(parameters);
_registrationPipeline = Registration::create(parameters);
_globalDescriptorExtractor = GlobalDescriptorExtractor::create(parameters);
if(!_registrationPipeline->isImageRequired())
{
// make sure feature matching is used instead of optical flow to compute the guess
ParametersMap tmp = parameters;
uInsert(tmp, ParametersPair(Parameters::kVisCorType(), "0"));
uInsert(tmp, ParametersPair(Parameters::kRegRepeatOnce(), "false"));
_registrationVis = new RegistrationVis(tmp);
}
// for local scan matching, correspondences ratio should be two times higher as we expect more matches
float corRatio = Parameters::defaultIcpCorrespondenceRatio();
Parameters::parse(parameters, Parameters::kIcpCorrespondenceRatio(), corRatio);
ParametersMap paramsMulti = parameters;
paramsMulti.insert(ParametersPair(Parameters::kIcpCorrespondenceRatio(), uNumber2Str(corRatio>=0.5f?1.0f:corRatio*2.0f)));
if(corRatio >= 0.5)
{
UWARN( "%s is >=0.5, which sets correspondence ratio for proximity detection using "
"laser scans to 100% (2 x Ratio). You may lower the ratio to accept proximity "
"detection with not full scans overlapping.", Parameters::kIcpCorrespondenceRatio().c_str());
}
_registrationIcpMulti = new RegistrationIcp(paramsMulti);
_localMapMaker = new LocalGridMaker(parameters);
_markerDetector = new MarkerDetector(parameters);
this->parseParameters(parameters);
}
bool Memory::init(const std::string & dbUrl, bool dbOverwritten, const ParametersMap & parameters, bool postInitClosingEvents)
{
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(RtabmapEventInit::kInitializing));
UDEBUG("");
this->parseParameters(parameters);
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Clearing memory..."));
DBDriver * tmpDriver = 0;
if((!_memoryChanged && !_linksChanged) || dbOverwritten)
{
if(_dbDriver)
{
tmpDriver = _dbDriver;
_dbDriver = 0; // HACK for the clear() below to think that there is no db
}
}
this->clear();
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Clearing memory, done!"));
if(tmpDriver)
{
_dbDriver = tmpDriver;
}
if(_dbDriver)
{
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Closing database connection..."));
_dbDriver->closeConnection();
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Closing database connection, done!"));
}
if(_dbDriver == 0)
{
_dbDriver = DBDriver::create(parameters);
}
bool success = true;
if(_dbDriver)
{
success = false;
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Connecting to database \"") + dbUrl + "\"..."));
if(_dbDriver->openConnection(dbUrl, dbOverwritten, isReadOnly()))
{
success = true;
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Connecting to database \"") + dbUrl + "\", done!"));
}
else
{
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(RtabmapEventInit::kError, std::string("Connecting to database ") + dbUrl + ", path is invalid!"));
}
}
loadDataFromDb(postInitClosingEvents);
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(RtabmapEventInit::kInitialized));
return success;
}
void Memory::loadDataFromDb(bool postInitClosingEvents)
{
if(_dbDriver && _dbDriver->isConnected())
{
bool loadAllNodesInWM = Parameters::defaultMemInitWMWithAllNodes();
Parameters::parse(parameters_, Parameters::kMemInitWMWithAllNodes(), loadAllNodesInWM);
// Load the last working memory...
std::list<Signature*> dbSignatures;
if(loadAllNodesInWM)
{
UDEBUG("Loading all nodes to WM...");
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Loading all nodes to WM...")));
std::set<int> ids;
_dbDriver->getAllNodeIds(ids, true);
_dbDriver->loadSignatures(std::list<int>(ids.begin(), ids.end()), dbSignatures, 0, !_loadVisualLocalFeaturesOnInit);
}
else
{
UDEBUG("Loading last nodes to WM...");
// load previous session working memory
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Loading last nodes to WM...")));
_dbDriver->loadLastNodes(dbSignatures, !_loadVisualLocalFeaturesOnInit);
}
for(std::list<Signature*>::reverse_iterator iter=dbSignatures.rbegin(); iter!=dbSignatures.rend(); ++iter)
{
// ignore bad signatures
if(!((*iter)->isBadSignature() && _badSignaturesIgnored))
{
// insert all in WM
// Note: it doesn't make sense to keep last STM images
// of the last session in the new STM because they can be
// only linked with the ones of the current session by
// global loop closures.
_signatures.insert(std::pair<int, Signature *>((*iter)->id(), *iter));
_workingMem.insert(std::make_pair((*iter)->id(), UTimer::now()));
if(!(*iter)->getGroundTruthPose().isNull()) {
_groundTruths.insert(std::make_pair((*iter)->id(), (*iter)->getGroundTruthPose()));
}
if(!(*iter)->getLandmarks().empty())
{
// Update landmark indexes
for(std::map<int, Link>::const_iterator jter = (*iter)->getLandmarks().begin(); jter!=(*iter)->getLandmarks().end(); ++jter)
{
int landmarkId = jter->first;
UASSERT(landmarkId < 0);
cv::Mat landmarkSize = jter->second.uncompressUserDataConst();
if(!landmarkSize.empty() && landmarkSize.type() == CV_32FC1 && landmarkSize.total()==1)
{
std::pair<std::map<int, float>::iterator, bool> inserted=_landmarksSize.insert(std::make_pair(-landmarkId, landmarkSize.at<float>(0,0)));
if(!inserted.second)
{
if(inserted.first->second != landmarkSize.at<float>(0,0))
{
UWARN("Trying to update landmark size buffer for landmark %d with size=%f but "
"it has already a different size set. Keeping old size (%f).",
-landmarkId, inserted.first->second, landmarkSize.at<float>(0,0));
}
}
else
{
UDEBUG("Caching landmark size %f for %d", landmarkSize.at<float>(0,0), -landmarkId);
}
}
std::map<int, std::set<int> >::iterator nter = _landmarksIndex.find(landmarkId);
if(nter!=_landmarksIndex.end())
{
nter->second.insert((*iter)->id());
}
else
{
std::set<int> tmp;
tmp.insert((*iter)->id());
_landmarksIndex.insert(std::make_pair(landmarkId, tmp));
}
}
}
}
else
{
delete *iter;
}
}
// Get labels
UDEBUG("Get labels");
_dbDriver->getAllLabels(_labels);
UDEBUG("Check if all nodes are in Working Memory");
for(std::map<int, Signature*>::iterator iter=_signatures.begin(); iter!=_signatures.end() && _allNodesInWM; ++iter)
{
for(std::map<int, Link>::const_iterator jter = iter->second->getLinks().begin(); jter!=iter->second->getLinks().end(); ++jter)
{
if(_signatures.find(jter->first) == _signatures.end())
{
_allNodesInWM = false;
break;
}
}
}
UDEBUG("allNodesInWM()=%s", _allNodesInWM?"true":"false");
UDEBUG("update odomMaxInf vector");
std::multimap<int, Link> links = this->getAllLinks(true, true);
for(std::multimap<int, Link>::iterator iter=links.begin(); iter!=links.end(); ++iter)
{
if(iter->second.type() == Link::kNeighbor &&
iter->second.infMatrix().cols == 6 &&
iter->second.infMatrix().rows == 6)
{
if(_odomMaxInf.empty())
{
_odomMaxInf.resize(6, 0.0);
}
for(int i=0; i<6; ++i)
{
const double & v = iter->second.infMatrix().at<double>(i,i);
if(_odomMaxInf[i] < v)
{
_odomMaxInf[i] = v;
}
}
}
}
UDEBUG("update odomMaxInf vector, done!");
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Loading nodes to WM, done! (") + uNumber2Str(int(_workingMem.size() + _stMem.size())) + " loaded)"));
// Assign the last signature
if(_stMem.size()>0)
{
_lastSignature = uValue(_signatures, *_stMem.rbegin(), (Signature*)0);
}
else if(_workingMem.size()>0)
{
_lastSignature = uValue(_signatures, _workingMem.rbegin()->first, (Signature*)0);
}
// Last id
_dbDriver->getLastNodeId(_idCount);
_idMapCount = -1;
_dbDriver->getLastMapId(_idMapCount);
++_idMapCount;
// Now load the dictionary if we have a connection
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Loading dictionary..."));
UDEBUG("Loading dictionary...");
if(loadAllNodesInWM)
{
UDEBUG("load all referenced words in working memory");
// load all referenced words in working memory
std::set<int> wordIds;
const std::map<int, Signature *> & signatures = this->getSignatures();
for(std::map<int, Signature *>::const_iterator i=signatures.begin(); i!=signatures.end(); ++i)
{
const std::multimap<int, int> & words = i->second->getWords();
std::list<int> keys = uUniqueKeys(words);
for(std::list<int>::iterator iter=keys.begin(); iter!=keys.end(); ++iter)
{
if(*iter > 0)
{
wordIds.insert(*iter);
}
}
}
UDEBUG("load words %d", (int)wordIds.size());
if(_vwd->isIncremental())
{
if(wordIds.size())
{
std::list<VisualWord*> words;
_dbDriver->loadWords(wordIds, words);
for(std::list<VisualWord*>::iterator iter = words.begin(); iter!=words.end(); ++iter)
{
_vwd->addWord(*iter);
}
// Get Last word id
int id = 0;
_dbDriver->getLastWordId(id);
_vwd->setLastWordId(id);
}
}
else
{
_dbDriver->load(*_vwd, false);
}
}
else
{
UDEBUG("load words");
// load the last dictionary
_dbDriver->load(*_vwd, _vwd->isIncremental());
}
UDEBUG("%d words loaded!", _vwd->getUnusedWordsSize());
_vwd->update();
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(uFormat("Loading dictionary, done! (%d words)", (int)_vwd->getUnusedWordsSize())));
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(std::string("Adding word references...")));
UDEBUG("Adding word references...");
UTimer timer;
// Enable loaded signatures
const std::map<int, Signature *> & signatures = this->getSignatures();
bool corruptedDictionary = false;
for(std::map<int, Signature *>::const_iterator i=signatures.begin(); i!=signatures.end() && !corruptedDictionary; ++i)
{
Signature * s = this->_getSignature(i->first);
UASSERT(s != 0);
const std::multimap<int, int> & words = s->getWords();
if(words.size())
{
//UDEBUG("node=%d, word references=%d", s->id(), words.size());
for(std::multimap<int, int>::const_iterator iter = words.begin(); iter!=words.end(); ++iter)
{
if(iter->first > 0)
{
if(!_vwd->addWordRef(iter->first, s->id()))
{
corruptedDictionary = true;
break;
}
}
}
s->setEnabled(!corruptedDictionary);
if(corruptedDictionary)
{
//revert all changes from that signature till it broke above
for(std::multimap<int, int>::const_iterator iter = words.begin(); iter!=words.end(); ++iter)
{
if(iter->first > 0)
{
_vwd->removeAllWordRef(iter->first, s->id());
}
}
}
}
}
if(corruptedDictionary)
{
if(!_vwd->isIncremental())
{
UERROR("The dictionary is empty or missing some words from nodes in WM, "
"we cannot repair it because it is a fixed dictionary. Make sure you "
"are using the right fixed dictionary that was used to generate the map.");
}
else
{
std::string msg = uFormat(
"The dictionary is empty or missing some words from nodes in WM, "
"we will try to repair it. This can be caused by rtabmap closing before it has time "
"to save the dictionary. Re-creating the dictionary from %ld nodes...",
signatures.size());
UWARN("%s", msg.c_str());
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(msg));
//remove all words ref
const std::map<int, VisualWord *> & addedWords = _vwd->getVisualWords();
int nodesRepaired = 0;
size_t oldSize = addedWords.size();
std::string assertMsg =
"If we assert here, the problem is maybe deeper. Try "
"to use rtabmap-recovery tool instead to fix the database.";
for(std::map<int, Signature *>::const_iterator i=signatures.begin(); i!=signatures.end(); ++i)
{
Signature * s = this->_getSignature(i->first);
UASSERT_MSG(s != 0, assertMsg.c_str());
if(s->isEnabled())
{
// Words already in dictionary and references added
continue;
}
const std::multimap<int, int> * words = &s->getWords();
if(words->size())
{
cv::Mat descriptors = s->getWordsDescriptors();
std::multimap<int, int> loadedWords;
if(descriptors.empty())
{
// We may have started rtabmap without loading features, check in the database
std::multimap<int, int> w;
std::vector<cv::KeyPoint> k;
std::vector<cv::Point3f> p;
_dbDriver->getLocalFeatures(s->id(), loadedWords, k, p, descriptors);
UASSERT_MSG(loadedWords.size() == words->size(), assertMsg.c_str()); // Just doublecheck
words = &loadedWords; // The index will be set
UASSERT_MSG(!descriptors.empty(), assertMsg.c_str());
}
bool repaired = false;
for(std::multimap<int, int>::const_iterator iter = words->begin(); iter!=words->end(); ++iter)
{
if(iter->first > 0)
{
if(addedWords.find(iter->first) == addedWords.end())
{
UASSERT_MSG(iter->second >= 0 && iter->second < descriptors.rows,
uFormat("iter->second=%d descriptors.rows=%d (signature=%d word=%d). %s",
iter->second, descriptors.rows, s->id(), iter->first, assertMsg.c_str()).c_str());
_vwd->addWord(new VisualWord(iter->first, descriptors.row(iter->second).clone()));
repaired = true;
}
UASSERT_MSG(_vwd->addWordRef(iter->first, s->id()), assertMsg.c_str());
}
}
nodesRepaired += (repaired?1:0);
s->setEnabled(true);
}
}
msg = uFormat(
"Regenerated the dictionary with %ld missing words (%ld -> %ld) from %d nodes.",
addedWords.size() - oldSize,
oldSize,
addedWords.size(),
nodesRepaired);
UWARN("%s", msg.c_str());
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(msg));
_memoryChanged = true; // This will force rtabmap to save back the dictionary even if we don't process any new data
_vwd->update();
}
}
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(uFormat("Adding word references, done! (%d)", _vwd->getTotalActiveReferences())));
if(_vwd->getUnusedWordsSize() && _vwd->isIncremental())
{
UWARN("_vwd->getUnusedWordsSize() must be empty... size=%d", _vwd->getUnusedWordsSize());
}
UDEBUG("Total word references added = %d (in %f s)", _vwd->getTotalActiveReferences(), timer.ticks());
if(_lastSignature == 0)
{
// Memory is empty, save parameters
ParametersMap parameters = Parameters::getDefaultParameters();
uInsert(parameters, parameters_);
parameters.erase(Parameters::kRtabmapWorkingDirectory()); // don't save working directory as it is machine dependent
UDEBUG("");
_dbDriver->addInfoAfterRun(0, 0, 0, 0, 0, parameters);
}
}
else
{
_idCount = kIdStart;
_idMapCount = kIdStart;
}
_workingMem.insert(std::make_pair(kIdVirtual, 0));
UDEBUG("ids start with %d", _idCount+1);
UDEBUG("map ids start with %d", _idMapCount);
}
void Memory::saveFlannIndex(bool postInitClosingEvents)
{
if(!_dbDriver) {
return;
}
if(uStrNumCmp(_dbDriver->getDatabaseVersion(), "0.23.0") >= 0) {
if(_flannIndexSaved && !_incrementalMemory) {
if(_vwd->isModified()) {
UINFO("Saving flann index to database... (%s=true)", Parameters::kKpFlannIndexSaved().c_str());
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Saving flann index to database..."));
_dbDriver->saveFlannIndex(_vwd->serializeIndex());
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Saving flann index to database, done!"));
}
else
{
UDEBUG("The dictionary didn't change since loaded, do not need to save again to database.");
}
}
else {
// clear if exists
_dbDriver->saveFlannIndex(std::vector<unsigned char>());
}
}
else if(_flannIndexSaved)
{
UWARN("Parameter %s is enabled, but database version is too old (%s < 0.23). Flann index cannot be saved.",
Parameters::kKpFlannIndexSaved().c_str(),
_dbDriver->getDatabaseVersion().c_str());
}
}
void Memory::close(bool databaseSaved, bool postInitClosingEvents, const std::string & ouputDatabasePath)
{
UINFO("databaseSaved=%d, postInitClosingEvents=%d", databaseSaved?1:0, postInitClosingEvents?1:0);
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(RtabmapEventInit::kClosing));
bool databaseNameChanged = false;
if(databaseSaved && _dbDriver)
{
databaseNameChanged = ouputDatabasePath.size() && _dbDriver->getUrl().size() && _dbDriver->getUrl().compare(ouputDatabasePath) != 0?true:false;
}
UDEBUG("_memoryChanged=%d _linksChanged=%d databaseNameChanged=%d", _memoryChanged?1:0, _linksChanged?1:0, databaseNameChanged?1:0);
if(!databaseSaved || (!_memoryChanged && !_linksChanged && !databaseNameChanged) || this->isReadOnly())
{
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(uFormat("No changes added to database.")));
UINFO("No changes added to database.");
if(_dbDriver)
{
if(!this->isReadOnly()) {
saveFlannIndex(postInitClosingEvents);
}
else if(_memoryChanged || _linksChanged || databaseNameChanged)
{
UWARN("Memory has been modified (nodes=%s links=%s name=%s) but the database is read-only, changes are not saved to database.",
_memoryChanged?"true":"false", _linksChanged?"true":"false", databaseNameChanged?"true":"false");
}
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(uFormat("Closing database \"%s\"...", _dbDriver->getUrl().c_str())));
_dbDriver->closeConnection(false);
delete _dbDriver;
_dbDriver = 0;
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Closing database, done!"));
}
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Clearing memory..."));
this->clear();
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Clearing memory, done!"));
}
else
{
UINFO("Saving memory...");
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Saving memory..."));
if(!_memoryChanged && _dbDriver)
{
saveFlannIndex(postInitClosingEvents);
}
this->clear();
if(_dbDriver)
{
_dbDriver->emptyTrashes();
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Saving memory, done!"));
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(uFormat("Closing database \"%s\"...", _dbDriver->getUrl().c_str())));
_dbDriver->closeConnection(true, ouputDatabasePath);
delete _dbDriver;
_dbDriver = 0;
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Closing database, done!"));
}
else
{
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit("Saving memory, done!"));
}
}
if(postInitClosingEvents) UEventsManager::post(new RtabmapEventInit(RtabmapEventInit::kClosed));
}
Memory::~Memory()
{
this->close();
if(_dbDriver)
{
UWARN("Please call Memory::close() before");
}
delete _feature2D;
delete _vwd;
delete _registrationPipeline;
delete _registrationIcpMulti;
delete _registrationVis;
delete _localMapMaker;
}
void Memory::parseParameters(const ParametersMap & parameters)
{
uInsert(parameters_, parameters);
ParametersMap params = parameters;
UDEBUG("");
ParametersMap::const_iterator iter;
Parameters::parse(params, Parameters::kMemBinDataKept(), _binDataKept);
Parameters::parse(params, Parameters::kMemRawDescriptorsKept(), _rawDescriptorsKept);
Parameters::parse(params, Parameters::kMemLoadVisualLocalFeaturesOnInit(), _loadVisualLocalFeaturesOnInit);
Parameters::parse(params, Parameters::kMemSaveDepth16Format(), _saveDepth16Format);
Parameters::parse(params, Parameters::kMemReduceGraph(), _reduceGraph);
Parameters::parse(params, Parameters::kMemNotLinkedNodesKept(), _notLinkedNodesKeptInDb);
Parameters::parse(params, Parameters::kMemIntermediateNodeDataKept(), _saveIntermediateNodeData);
Parameters::parse(params, Parameters::kMemImageCompressionFormat(), _rgbCompressionFormat);
Parameters::parse(params, Parameters::kMemDepthCompressionFormat(), _depthCompressionFormat);
Parameters::parse(params, Parameters::kMemRehearsalIdUpdatedToNewOne(), _idUpdatedToNewOneRehearsal);
Parameters::parse(params, Parameters::kMemGenerateIds(), _generateIds);
Parameters::parse(params, Parameters::kMemBadSignaturesIgnored(), _badSignaturesIgnored);
Parameters::parse(params, Parameters::kMemMapLabelsAdded(), _mapLabelsAdded);
Parameters::parse(params, Parameters::kMemRehearsalSimilarity(), _similarityThreshold);
Parameters::parse(params, Parameters::kMemRecentWmRatio(), _recentWmRatio);
Parameters::parse(params, Parameters::kMemTransferSortingByWeightId(), _transferSortingByWeightId);
Parameters::parse(params, Parameters::kMemSTMSize(), _maxStMemSize);
Parameters::parse(params, Parameters::kMemDepthAsMask(), _depthAsMask);
Parameters::parse(params, Parameters::kMemDepthMaskFloorThr(), _maskFloorThreshold);
Parameters::parse(params, Parameters::kMemStereoFromMotion(), _stereoFromMotion);
Parameters::parse(params, Parameters::kMemImagePreDecimation(), _imagePreDecimation);
Parameters::parse(params, Parameters::kMemImagePostDecimation(), _imagePostDecimation);
Parameters::parse(params, Parameters::kMemCompressionParallelized(), _compressionParallelized);
Parameters::parse(params, Parameters::kMemLaserScanDownsampleStepSize(), _laserScanDownsampleStepSize);
Parameters::parse(params, Parameters::kMemLaserScanVoxelSize(), _laserScanVoxelSize);
Parameters::parse(params, Parameters::kMemLaserScanNormalK(), _laserScanNormalK);
Parameters::parse(params, Parameters::kMemLaserScanNormalRadius(), _laserScanNormalRadius);
Parameters::parse(params, Parameters::kIcpPointToPlaneGroundNormalsUp(), _laserScanGroundNormalsUp);
Parameters::parse(params, Parameters::kRGBDLoopClosureReextractFeatures(), _reextractLoopClosureFeatures);
Parameters::parse(params, Parameters::kRGBDLocalBundleOnLoopClosure(), _localBundleOnLoopClosure);
Parameters::parse(params, Parameters::kRGBDInvertedReg(), _invertedReg);
if(_invertedReg && _localBundleOnLoopClosure)
{
UWARN("%s and %s cannot be used at the same time, disabling %s...",
Parameters::kRGBDLocalBundleOnLoopClosure().c_str(),
Parameters::kRGBDInvertedReg().c_str(),
Parameters::kRGBDLocalBundleOnLoopClosure().c_str());
_localBundleOnLoopClosure = false;
}
Parameters::parse(params, Parameters::kRGBDLinearUpdate(), _rehearsalMaxDistance);
Parameters::parse(params, Parameters::kRGBDAngularUpdate(), _rehearsalMaxAngle);
Parameters::parse(params, Parameters::kMemRehearsalWeightIgnoredWhileMoving(), _rehearsalWeightIgnoredWhileMoving);
Parameters::parse(params, Parameters::kMemUseOdomFeatures(), _useOdometryFeatures);
Parameters::parse(params, Parameters::kMemUseOdomGravity(), _useOdometryGravity);
Parameters::parse(params, Parameters::kMemRotateImagesUpsideUp(), _rotateImagesUpsideUp);
Parameters::parse(params, Parameters::kRGBDCreateOccupancyGrid(), _createOccupancyGrid);
Parameters::parse(params, Parameters::kVisMaxFeatures(), _visMaxFeatures);
Parameters::parse(params, Parameters::kVisSSC(), _visSSC);
Parameters::parse(params, Parameters::kRtabmapImagesAlreadyRectified(), _imagesAlreadyRectified);
Parameters::parse(params, Parameters::kRtabmapRectifyOnlyFeatures(), _rectifyOnlyFeatures);
Parameters::parse(params, Parameters::kMemCovOffDiagIgnored(), _covOffDiagonalIgnored);
Parameters::parse(params, Parameters::kRGBDMarkerDetection(), _detectMarkers);
Parameters::parse(params, Parameters::kMarkerVarianceLinear(), _markerLinVariance);
Parameters::parse(params, Parameters::kMarkerVarianceAngular(), _markerAngVariance);
Parameters::parse(params, Parameters::kMarkerVarianceOrientationIgnored(), _markerOrientationIgnored);
Parameters::parse(params, Parameters::kMemLocalizationDataSaved(), _localizationDataSaved);
Parameters::parse(params, Parameters::kKpFlannIndexSaved(), _flannIndexSaved);
Parameters::parse(params, Parameters::kMemLocalizationReadOnly(), _localizationReadOnly);
if(_markerAngVariance>=9999)
{
UWARN("Using directly %s>=9999 to ignore marker orientation is deprecated. Use %s instead and "
"read correctly the description of the new parameter. We will enable %s and set %s to "
"same value than %s (%f) for backward compatibility.",
Parameters::kMarkerVarianceAngular().c_str(),
Parameters::kMarkerVarianceOrientationIgnored().c_str(),
Parameters::kMarkerVarianceOrientationIgnored().c_str(),
Parameters::kMarkerVarianceAngular().c_str(),
Parameters::kMarkerVarianceLinear().c_str(),
_markerLinVariance);
_markerAngVariance = _markerLinVariance;
_markerOrientationIgnored = true;
}
UASSERT_MSG(_maxStMemSize >= 0, uFormat("value=%d", _maxStMemSize).c_str());
UASSERT_MSG(_similarityThreshold >= 0.0f && _similarityThreshold <= 1.0f, uFormat("value=%f", _similarityThreshold).c_str());
UASSERT_MSG(_recentWmRatio >= 0.0f && _recentWmRatio <= 1.0f, uFormat("value=%f", _recentWmRatio).c_str());
if(_imagePreDecimation == 0)
{
_imagePreDecimation = 1;
}
if(_imagePostDecimation == 0)
{
_imagePostDecimation = 1;
}
UASSERT(_rehearsalMaxDistance >= 0.0f);
UASSERT(_rehearsalMaxAngle >= 0.0f);
if(_dbDriver)
{
_dbDriver->parseParameters(params);
}
// Keypoint stuff
_vwd->parseParameters(params);
Parameters::parse(params, Parameters::kKpTfIdfLikelihoodUsed(), _tfIdfLikelihoodUsed);
Parameters::parse(params, Parameters::kKpParallelized(), _parallelized);
Parameters::parse(params, Parameters::kKpBadSignRatio(), _badSignRatio);
//Keypoint detector
UASSERT(_feature2D != 0);
Feature2D::Type detectorStrategy = Feature2D::kFeatureUndef;
if((iter=params.find(Parameters::kKpDetectorStrategy())) != params.end())
{
detectorStrategy = (Feature2D::Type)std::atoi((*iter).second.c_str());
}
if(detectorStrategy!=Feature2D::kFeatureUndef && detectorStrategy!=_feature2D->getType())
{
if(_vwd->getVisualWords().size())
{
UWARN("new detector strategy %d while the vocabulary is already created. This may give problems if feature descriptors are not the same type than the one used in the current vocabulary (a memory reset would be required if so).", int(detectorStrategy));
}
else
{
UINFO("new detector strategy %d.", int(detectorStrategy));
}
if(_feature2D)
{
delete _feature2D;
_feature2D = 0;
}
_feature2D = Feature2D::create(detectorStrategy, parameters_);
}
else if(_feature2D)
{
_feature2D->parseParameters(params);
}
// Features Matching is the only correspondence approach supported for loop closure transformation estimation.
uInsert(parameters_, ParametersPair(Parameters::kVisCorType(), "0"));
uInsert(params, ParametersPair(Parameters::kVisCorType(), "0"));
Registration::Type currentStrategy = Registration::kTypeUndef;
if(_registrationPipeline)
{
if(_registrationPipeline->isImageRequired() && _registrationPipeline->isScanRequired())
{
currentStrategy = Registration::kTypeVisIcp;
}
else if(_registrationPipeline->isImageRequired())
{
currentStrategy = Registration::kTypeVis;
}
else if(_registrationPipeline->isScanRequired())
{
currentStrategy = Registration::kTypeIcp;
}
}
Registration::Type regStrategy = Registration::kTypeUndef;
if((iter=params.find(Parameters::kRegStrategy())) != params.end())
{
regStrategy = (Registration::Type)std::atoi((*iter).second.c_str());
}
if(regStrategy!=Registration::kTypeUndef && regStrategy != currentStrategy)
{
UDEBUG("new registration strategy %d", int(regStrategy));
if(_registrationPipeline)
{
delete _registrationPipeline;
_registrationPipeline = 0;
}
_registrationPipeline = Registration::create(regStrategy, parameters_);
if(!_registrationPipeline->isImageRequired() && _registrationVis == 0)
{
ParametersMap tmp = params;
uInsert(tmp, ParametersPair(Parameters::kRegRepeatOnce(), "false"));
_registrationVis = new RegistrationVis(tmp);
}
else if(_registrationPipeline->isImageRequired() && _registrationVis)
{
delete _registrationVis;
_registrationVis = 0;
}
}
else if(_registrationPipeline)
{
_registrationPipeline->parseParameters(params);
if(_registrationVis)
{
ParametersMap tmp = params;
uInsert(tmp, ParametersPair(Parameters::kRegRepeatOnce(), "false"));
_registrationVis->parseParameters(tmp);
}
}
if(_registrationIcpMulti)
{
if(uContains(params, Parameters::kIcpCorrespondenceRatio()))
{
// for local scan matching, correspondences ratio should be two times higher as we expect more matches
float corRatio = Parameters::defaultIcpCorrespondenceRatio();
Parameters::parse(parameters, Parameters::kIcpCorrespondenceRatio(), corRatio);
ParametersMap paramsMulti = params;
uInsert(paramsMulti, ParametersPair(Parameters::kIcpCorrespondenceRatio(), uNumber2Str(corRatio>=0.5f?1.0f:corRatio*2.0f)));
if(corRatio >= 0.5)
{
UWARN( "%s is >=0.5, which sets correspondence ratio for proximity detection using "
"laser scans to 100% (2 x Ratio). You may lower the ratio to accept proximity "
"detection with not full scans overlapping.", Parameters::kIcpCorrespondenceRatio().c_str());
}
_registrationIcpMulti->parseParameters(paramsMulti);
}
else
{
_registrationIcpMulti->parseParameters(params);
}
}
if(_localMapMaker)
{
_localMapMaker->parseParameters(params);
}
if(_markerDetector)
{
_markerDetector->parseParameters(params);
}
int globalDescriptorStrategy = -1;
Parameters::parse(params, Parameters::kMemGlobalDescriptorStrategy(), globalDescriptorStrategy);
if(globalDescriptorStrategy != -1 &&
(_globalDescriptorExtractor==0 || (int)_globalDescriptorExtractor->getType() != globalDescriptorStrategy))
{
if(_globalDescriptorExtractor)
{
delete _globalDescriptorExtractor;
}
_globalDescriptorExtractor = GlobalDescriptorExtractor::create(parameters_);
}
else if(_globalDescriptorExtractor)
{
_globalDescriptorExtractor->parseParameters(params);
}
// do this after all params are parsed
// SLAM mode vs Localization mode
iter = params.find(Parameters::kMemIncrementalMemory());
if(iter != params.end())
{
bool value = uStr2Bool(iter->second.c_str());
if(value == false && _incrementalMemory)
{
// From SLAM to localization, change map id
this->incrementMapId();
// The easiest way to make sure that the mapping session is saved
// is to save the memory in the database and reload it.
if((_memoryChanged || _linksChanged) && _dbDriver)
{
UWARN("Switching from Mapping to Localization mode, the database will be saved and reloaded.");
bool memoryChanged = _memoryChanged;
bool linksChanged = _linksChanged;
this->clear();
_memoryChanged = memoryChanged;
_linksChanged = linksChanged;
this->loadDataFromDb(false);
UWARN("Switching from Mapping to Localization mode, the database is reloaded!");
}
}
_incrementalMemory = value;
}
if(_useOdometryFeatures)
{
int visFeatureType = Parameters::defaultVisFeatureType();
int kpDetectorStrategy = Parameters::defaultKpDetectorStrategy();
Parameters::parse(parameters_, Parameters::kVisFeatureType(), visFeatureType);
Parameters::parse(parameters_, Parameters::kKpDetectorStrategy(), kpDetectorStrategy);
if(visFeatureType != kpDetectorStrategy)
{
UWARN("%s is enabled, but %s and %s parameters are not the same! Disabling %s...",
Parameters::kMemUseOdomFeatures().c_str(),
Parameters::kVisFeatureType().c_str(),
Parameters::kKpDetectorStrategy().c_str(),
Parameters::kMemUseOdomFeatures().c_str());
_useOdometryFeatures = false;
uInsert(parameters_, ParametersPair(Parameters::kMemUseOdomFeatures(), "false"));
}
}
}
void Memory::preUpdate()
{
_signaturesAdded = 0;