/
Rtabmap.cpp
3873 lines (3582 loc) · 131 KB
/
Rtabmap.cpp
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-2014, 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/core/Rtabmap.h"
#include "rtabmap/core/Version.h"
#include "rtabmap/core/Features2d.h"
#include "rtabmap/core/Graph.h"
#include "rtabmap/core/Signature.h"
#include "rtabmap/core/EpipolarGeometry.h"
#include "rtabmap/core/Memory.h"
#include "rtabmap/core/VWDictionary.h"
#include "rtabmap/core/BayesFilter.h"
#include "rtabmap/core/Compression.h"
#include <rtabmap/utilite/ULogger.h>
#include <rtabmap/utilite/UFile.h>
#include <rtabmap/utilite/UTimer.h>
#include <rtabmap/utilite/UConversion.h>
#include <rtabmap/utilite/UMath.h>
#include "SimpleIni.h"
#include <pcl/search/kdtree.h>
#include <pcl/filters/crop_box.h>
#include <pcl/io/pcd_io.h>
#include <stdlib.h>
#include <set>
#define LOG_F "LogF.txt"
#define LOG_I "LogI.txt"
#define GRAPH_FILE_NAME "Graph.dot"
//
//
//
// =======================================================
// MAIN LOOP, see method "void Rtabmap::process();" below.
// =======================================================
//
//
//
namespace rtabmap
{
Rtabmap::Rtabmap() :
_publishStats(Parameters::defaultRtabmapPublishStats()),
_publishLastSignatureData(Parameters::defaultRtabmapPublishLastSignature()),
_publishPdf(Parameters::defaultRtabmapPublishPdf()),
_publishLikelihood(Parameters::defaultRtabmapPublishLikelihood()),
_maxTimeAllowed(Parameters::defaultRtabmapTimeThr()), // 700 ms
_maxMemoryAllowed(Parameters::defaultRtabmapMemoryThr()), // 0=inf
_loopThr(Parameters::defaultRtabmapLoopThr()),
_loopRatio(Parameters::defaultRtabmapLoopRatio()),
_maxRetrieved(Parameters::defaultRtabmapMaxRetrieved()),
_maxLocalRetrieved(Parameters::defaultRGBDMaxLocalRetrieved()),
_statisticLogsBufferedInRAM(Parameters::defaultRtabmapStatisticLogsBufferedInRAM()),
_statisticLogged(Parameters::defaultRtabmapStatisticLogged()),
_statisticLoggedHeaders(Parameters::defaultRtabmapStatisticLoggedHeaders()),
_rgbdSlamMode(Parameters::defaultRGBDEnabled()),
_rgbdLinearUpdate(Parameters::defaultRGBDLinearUpdate()),
_rgbdAngularUpdate(Parameters::defaultRGBDAngularUpdate()),
_newMapOdomChangeDistance(Parameters::defaultRGBDNewMapOdomChangeDistance()),
_globalLoopClosureIcpType(Parameters::defaultLccIcpType()),
_poseScanMatching(Parameters::defaultRGBDPoseScanMatching()),
_localLoopClosureDetectionTime(Parameters::defaultRGBDLocalLoopDetectionTime()),
_localLoopClosureDetectionSpace(Parameters::defaultRGBDLocalLoopDetectionSpace()),
_scanMatchingIdsSavedInLinks(Parameters::defaultRGBDScanMatchingIdsSavedInLinks()),
_localRadius(Parameters::defaultRGBDLocalRadius()),
_localImmunizationRatio(Parameters::defaultRGBDLocalImmunizationRatio()),
_localDetectMaxGraphDepth(Parameters::defaultRGBDLocalLoopDetectionMaxGraphDepth()),
_localPathFilteringRadius(Parameters::defaultRGBDLocalLoopDetectionPathFilteringRadius()),
_localPathOdomPosesUsed(Parameters::defaultRGBDLocalLoopDetectionPathOdomPosesUsed()),
_databasePath(""),
_optimizeFromGraphEnd(Parameters::defaultRGBDOptimizeFromGraphEnd()),
_optimizationMaxLinearError(Parameters::defaultRGBDOptimizeMaxError()),
_reextractLoopClosureFeatures(Parameters::defaultLccReextractActivated()),
_reextractNNType(Parameters::defaultLccReextractNNType()),
_reextractNNDR(Parameters::defaultLccReextractNNDR()),
_reextractFeatureType(Parameters::defaultLccReextractFeatureType()),
_reextractMaxWords(Parameters::defaultLccReextractMaxWords()),
_reextractMaxDepth(Parameters::defaultLccReextractMaxDepth()),
_startNewMapOnLoopClosure(Parameters::defaultRtabmapStartNewMapOnLoopClosure()),
_goalReachedRadius(Parameters::defaultRGBDGoalReachedRadius()),
_goalsSavedInUserData(Parameters::defaultRGBDGoalsSavedInUserData()),
_pathStuckIterations(Parameters::defaultRGBDPlanStuckIterations()),
_pathLinearVelocity(Parameters::defaultRGBDPlanLinearVelocity()),
_pathAngularVelocity(Parameters::defaultRGBDPlanAngularVelocity()),
_loopClosureHypothesis(0,0.0f),
_highestHypothesis(0,0.0f),
_lastProcessTime(0.0),
_someNodesHaveBeenTransferred(false),
_distanceTravelled(0.0f),
_epipolarGeometry(0),
_bayesFilter(0),
_graphOptimizer(0),
_memory(0),
_foutFloat(0),
_foutInt(0),
_wDir("."),
_mapCorrection(Transform::getIdentity()),
_lastLocalizationNodeId(0),
_pathStatus(0),
_pathCurrentIndex(0),
_pathGoalIndex(0),
_pathTransformToGoal(Transform::getIdentity()),
_pathStuckCount(0)
{
}
Rtabmap::~Rtabmap() {
UDEBUG("");
this->close();
}
std::string Rtabmap::getVersion()
{
return RTABMAP_VERSION;
return ""; // Second return only to avoid compiler warning with RTABMAP_VERSION not yet set.
}
void Rtabmap::setupLogFiles(bool overwrite)
{
flushStatisticLogs();
// Log files
if(_foutFloat)
{
fclose(_foutFloat);
_foutFloat = 0;
}
if(_foutInt)
{
fclose(_foutInt);
_foutInt = 0;
}
if(_statisticLogged)
{
std::string attributes = "a+"; // append to log files
if(overwrite)
{
// If a file with the same name already exists
// its content is erased and the file is treated
// as a new empty file.
attributes = "w";
}
bool addLogFHeader = overwrite || !UFile::exists(_wDir+"/"+LOG_F);
bool addLogIHeader = overwrite || !UFile::exists(_wDir+"/"+LOG_I);
#ifdef _MSC_VER
fopen_s(&_foutFloat, (_wDir+"/"+LOG_F).c_str(), attributes.c_str());
fopen_s(&_foutInt, (_wDir+"/"+LOG_I).c_str(), attributes.c_str());
#else
_foutFloat = fopen((_wDir+"/"+LOG_F).c_str(), attributes.c_str());
_foutInt = fopen((_wDir+"/"+LOG_I).c_str(), attributes.c_str());
#endif
// add header (column identification)
if(_statisticLoggedHeaders && addLogFHeader && _foutFloat)
{
fprintf(_foutFloat, "Column headers:\n");
fprintf(_foutFloat, " 1-Total iteration time (s)\n");
fprintf(_foutFloat, " 2-Memory update time (s)\n");
fprintf(_foutFloat, " 3-Retrieval time (s)\n");
fprintf(_foutFloat, " 4-Likelihood time (s)\n");
fprintf(_foutFloat, " 5-Posterior time (s)\n");
fprintf(_foutFloat, " 6-Hypothesis selection time (s)\n");
fprintf(_foutFloat, " 7-Hypothesis validation time (s)\n");
fprintf(_foutFloat, " 8-Transfer time (s)\n");
fprintf(_foutFloat, " 9-Statistics creation time (s)\n");
fprintf(_foutFloat, " 10-Loop closure hypothesis value\n");
fprintf(_foutFloat, " 11-NAN\n");
fprintf(_foutFloat, " 12-NAN\n");
fprintf(_foutFloat, " 13-NAN\n");
fprintf(_foutFloat, " 14-NAN\n");
fprintf(_foutFloat, " 15-NAN\n");
fprintf(_foutFloat, " 16-Virtual place hypothesis\n");
fprintf(_foutFloat, " 17-Join trash time (s)\n");
fprintf(_foutFloat, " 18-Weight Update (rehearsal) similarity\n");
fprintf(_foutFloat, " 19-Empty trash time (s)\n");
fprintf(_foutFloat, " 20-Retrieval database access time (s)\n");
fprintf(_foutFloat, " 21-Add loop closure link time (s)\n");
fprintf(_foutFloat, " 22-Memory cleanup time (s)\n");
fprintf(_foutFloat, " 23-Scan matching (odometry correction) time (s)\n");
fprintf(_foutFloat, " 24-Local time loop closure detection time (s)\n");
fprintf(_foutFloat, " 25-Local space loop closure detection time (s)\n");
fprintf(_foutFloat, " 26-Map optimization (s)\n");
}
if(_statisticLoggedHeaders && addLogIHeader && _foutInt)
{
fprintf(_foutInt, "Column headers:\n");
fprintf(_foutInt, " 1-Loop closure ID\n");
fprintf(_foutInt, " 2-Highest loop closure hypothesis\n");
fprintf(_foutInt, " 3-Locations transferred\n");
fprintf(_foutInt, " 4-NAN\n");
fprintf(_foutInt, " 5-Words extracted from the last image\n");
fprintf(_foutInt, " 6-Vocabulary size\n");
fprintf(_foutInt, " 7-Working memory size\n");
fprintf(_foutInt, " 8-Is loop closure hypothesis rejected?\n");
fprintf(_foutInt, " 9-NAN\n");
fprintf(_foutInt, " 10-NAN\n");
fprintf(_foutInt, " 11-Locations retrieved\n");
fprintf(_foutInt, " 12-Retrieval location ID\n");
fprintf(_foutInt, " 13-Unique words extraced from last image\n");
fprintf(_foutInt, " 14-Retrieval ID\n");
fprintf(_foutInt, " 15-Non-null likelihood values\n");
fprintf(_foutInt, " 16-Weight Update ID\n");
fprintf(_foutInt, " 17-Is last location merged through Weight Update?\n");
fprintf(_foutInt, " 18-Local graph size\n");
fprintf(_foutInt, " 19-Sensor data id\n");
fprintf(_foutInt, " 20-Indexed words\n");
fprintf(_foutInt, " 21-Index memory usage (KB)\n");
}
ULOGGER_DEBUG("Log file (int)=%s", (_wDir+"/"+LOG_I).c_str());
ULOGGER_DEBUG("Log file (float)=%s", (_wDir+"/"+LOG_F).c_str());
}
else
{
UDEBUG("Log disabled!");
}
}
void Rtabmap::flushStatisticLogs()
{
if(_foutFloat && _bufferedLogsF.size())
{
UDEBUG("_bufferedLogsF.size=%d", _bufferedLogsF.size());
for(std::list<std::string>::iterator iter = _bufferedLogsF.begin(); iter!=_bufferedLogsF.end(); ++iter)
{
fprintf(_foutFloat, "%s", iter->c_str());
}
_bufferedLogsF.clear();
}
if(_foutInt && _bufferedLogsI.size())
{
UDEBUG("_bufferedLogsI.size=%d", _bufferedLogsI.size());
for(std::list<std::string>::iterator iter = _bufferedLogsI.begin(); iter!=_bufferedLogsI.end(); ++iter)
{
fprintf(_foutInt, "%s", iter->c_str());
}
_bufferedLogsI.clear();
}
}
void Rtabmap::init(const ParametersMap & parameters, const std::string & databasePath)
{
ParametersMap::const_iterator iter;
if((iter=parameters.find(Parameters::kRtabmapWorkingDirectory())) != parameters.end())
{
this->setWorkingDirectory(iter->second.c_str());
}
_databasePath = databasePath;
if(!_databasePath.empty())
{
UASSERT(UFile::getExtension(_databasePath).compare("db") == 0);
UINFO("Using database \"%s\".", _databasePath.c_str());
}
else
{
UWARN("Using empty database. Mapping session will not be saved.");
}
bool newDatabase = _databasePath.empty() || !UFile::exists(_databasePath);
// If not exist, create a memory
if(!_memory)
{
_memory = new Memory(parameters);
_memory->init(_databasePath, false, parameters, true);
}
// Parse all parameters
this->parseParameters(parameters);
if(_databasePath.empty())
{
_statisticLogged = false;
}
setupLogFiles(newDatabase);
}
void Rtabmap::init(const std::string & configFile, const std::string & databasePath)
{
// fill ctrl struct with values from the configuration file
ParametersMap param;// = Parameters::defaultParameters;
if(!configFile.empty())
{
ULOGGER_DEBUG("Read parameters from = %s", configFile.c_str());
this->readParameters(configFile, param);
}
this->init(param, databasePath);
}
void Rtabmap::close()
{
UINFO("");
_highestHypothesis = std::make_pair(0,0.0f);
_loopClosureHypothesis = std::make_pair(0,0.0f);
_lastProcessTime = 0.0;
_someNodesHaveBeenTransferred = false;
_optimizedPoses.clear();
_constraints.clear();
_mapCorrection.setIdentity();
_lastLocalizationPose.setNull();
_lastLocalizationNodeId = 0;
_distanceTravelled = 0.0f;
this->clearPath(0);
flushStatisticLogs();
if(_foutFloat)
{
fclose(_foutFloat);
_foutFloat = 0;
}
if(_foutInt)
{
fclose(_foutInt);
_foutInt = 0;
}
if(_epipolarGeometry)
{
delete _epipolarGeometry;
_epipolarGeometry = 0;
}
if(_memory)
{
delete _memory;
_memory = 0;
}
if(_bayesFilter)
{
delete _bayesFilter;
_bayesFilter = 0;
}
if(_graphOptimizer)
{
delete _graphOptimizer;
_graphOptimizer = 0;
}
_databasePath.clear();
parseParameters(Parameters::getDefaultParameters()); // reset to default parameters
_modifiedParameters.clear();
}
void Rtabmap::parseParameters(const ParametersMap & parameters)
{
ULOGGER_DEBUG("");
ParametersMap::const_iterator iter;
if((iter=parameters.find(Parameters::kRtabmapWorkingDirectory())) != parameters.end())
{
this->setWorkingDirectory(iter->second.c_str());
}
Parameters::parse(parameters, Parameters::kRtabmapPublishStats(), _publishStats);
Parameters::parse(parameters, Parameters::kRtabmapPublishLastSignature(), _publishLastSignatureData);
Parameters::parse(parameters, Parameters::kRtabmapPublishPdf(), _publishPdf);
Parameters::parse(parameters, Parameters::kRtabmapPublishLikelihood(), _publishLikelihood);
Parameters::parse(parameters, Parameters::kRtabmapTimeThr(), _maxTimeAllowed);
Parameters::parse(parameters, Parameters::kRtabmapMemoryThr(), _maxMemoryAllowed);
Parameters::parse(parameters, Parameters::kRtabmapLoopThr(), _loopThr);
Parameters::parse(parameters, Parameters::kRtabmapLoopRatio(), _loopRatio);
Parameters::parse(parameters, Parameters::kRtabmapMaxRetrieved(), _maxRetrieved);
Parameters::parse(parameters, Parameters::kRGBDMaxLocalRetrieved(), _maxLocalRetrieved);
Parameters::parse(parameters, Parameters::kRtabmapStatisticLogsBufferedInRAM(), _statisticLogsBufferedInRAM);
Parameters::parse(parameters, Parameters::kRtabmapStatisticLogged(), _statisticLogged);
Parameters::parse(parameters, Parameters::kRtabmapStatisticLoggedHeaders(), _statisticLoggedHeaders);
Parameters::parse(parameters, Parameters::kRGBDEnabled(), _rgbdSlamMode);
Parameters::parse(parameters, Parameters::kRGBDLinearUpdate(), _rgbdLinearUpdate);
Parameters::parse(parameters, Parameters::kRGBDAngularUpdate(), _rgbdAngularUpdate);
Parameters::parse(parameters, Parameters::kRGBDNewMapOdomChangeDistance(), _newMapOdomChangeDistance);
Parameters::parse(parameters, Parameters::kRGBDPoseScanMatching(), _poseScanMatching);
Parameters::parse(parameters, Parameters::kRGBDLocalLoopDetectionTime(), _localLoopClosureDetectionTime);
Parameters::parse(parameters, Parameters::kRGBDLocalLoopDetectionSpace(), _localLoopClosureDetectionSpace);
Parameters::parse(parameters, Parameters::kRGBDScanMatchingIdsSavedInLinks(), _scanMatchingIdsSavedInLinks);
Parameters::parse(parameters, Parameters::kRGBDLocalRadius(), _localRadius);
Parameters::parse(parameters, Parameters::kRGBDLocalImmunizationRatio(), _localImmunizationRatio);
Parameters::parse(parameters, Parameters::kRGBDLocalLoopDetectionMaxGraphDepth(), _localDetectMaxGraphDepth);
Parameters::parse(parameters, Parameters::kRGBDLocalLoopDetectionPathFilteringRadius(), _localPathFilteringRadius);
Parameters::parse(parameters, Parameters::kRGBDLocalLoopDetectionPathOdomPosesUsed(), _localPathOdomPosesUsed);
Parameters::parse(parameters, Parameters::kRGBDOptimizeFromGraphEnd(), _optimizeFromGraphEnd);
Parameters::parse(parameters, Parameters::kRGBDOptimizeMaxError(), _optimizationMaxLinearError);
Parameters::parse(parameters, Parameters::kLccReextractActivated(), _reextractLoopClosureFeatures);
Parameters::parse(parameters, Parameters::kLccReextractNNType(), _reextractNNType);
Parameters::parse(parameters, Parameters::kLccReextractNNDR(), _reextractNNDR);
Parameters::parse(parameters, Parameters::kLccReextractFeatureType(), _reextractFeatureType);
Parameters::parse(parameters, Parameters::kLccReextractMaxWords(), _reextractMaxWords);
Parameters::parse(parameters, Parameters::kLccReextractMaxDepth(), _reextractMaxDepth);
Parameters::parse(parameters, Parameters::kRtabmapStartNewMapOnLoopClosure(), _startNewMapOnLoopClosure);
Parameters::parse(parameters, Parameters::kRGBDGoalReachedRadius(), _goalReachedRadius);
Parameters::parse(parameters, Parameters::kRGBDGoalsSavedInUserData(), _goalsSavedInUserData);
Parameters::parse(parameters, Parameters::kRGBDPlanStuckIterations(), _pathStuckIterations);
Parameters::parse(parameters, Parameters::kRGBDPlanLinearVelocity(), _pathLinearVelocity);
Parameters::parse(parameters, Parameters::kRGBDPlanAngularVelocity(), _pathAngularVelocity);
UASSERT(_rgbdLinearUpdate >= 0.0f);
UASSERT(_rgbdAngularUpdate >= 0.0f);
// RGB-D SLAM stuff
if((iter=parameters.find(Parameters::kLccIcpType())) != parameters.end())
{
int icpType = std::atoi((*iter).second.c_str());
if(icpType >= 0 && icpType <= 2)
{
_globalLoopClosureIcpType = icpType;
}
else
{
UERROR("Icp type must be 0, 1 or 2 (value=%d)", icpType);
}
}
// By default, we create our strategies if they are not already created.
// If they already exists, we check the parameters if a change is requested
// Graph optimizer
graph::Optimizer::Type optimizerType = graph::Optimizer::kTypeUndef;
if((iter=parameters.find(Parameters::kRGBDOptimizeStrategy())) != parameters.end())
{
optimizerType = (graph::Optimizer::Type)std::atoi((*iter).second.c_str());
}
if(optimizerType!=graph::Optimizer::kTypeUndef)
{
UDEBUG("new detector strategy %d", int(optimizerType));
if(_graphOptimizer)
{
delete _graphOptimizer;
_graphOptimizer = 0;
}
_graphOptimizer = graph::Optimizer::create(optimizerType, parameters);
}
else if(_graphOptimizer)
{
_graphOptimizer->parseParameters(parameters);
}
else
{
optimizerType = (graph::Optimizer::Type)Parameters::defaultRGBDOptimizeStrategy();
_graphOptimizer = graph::Optimizer::create(optimizerType, parameters);
}
if(_memory)
{
_memory->parseParameters(parameters);
}
VhStrategy vhStrategy = kVhUndef;
// Verifying hypotheses strategy
if((iter=parameters.find(Parameters::kRtabmapVhStrategy())) != parameters.end())
{
vhStrategy = (VhStrategy)std::atoi((*iter).second.c_str());
}
if(!_epipolarGeometry && vhStrategy == kVhEpipolar)
{
_epipolarGeometry = new EpipolarGeometry(parameters);
}
else if(_epipolarGeometry && vhStrategy == kVhNone)
{
delete _epipolarGeometry;
_epipolarGeometry = 0;
}
else if(_epipolarGeometry)
{
_epipolarGeometry->parseParameters(parameters);
}
// Bayes filter, create one if not exists
if(!_bayesFilter)
{
_bayesFilter = new BayesFilter(parameters);
}
else
{
_bayesFilter->parseParameters(parameters);
}
for(ParametersMap::const_iterator iter = parameters.begin(); iter!=parameters.end(); ++iter)
{
uInsert(_modifiedParameters, ParametersPair(iter->first, iter->second));
}
}
int Rtabmap::getLastLocationId() const
{
int id = 0;
if(_memory)
{
id = _memory->getLastSignatureId();
}
return id;
}
std::list<int> Rtabmap::getWM() const
{
std::list<int> mem;
if(_memory)
{
mem = uKeysList(_memory->getWorkingMem());
mem.remove(-1);// Ignore the virtual signature (if here)
}
return mem;
}
int Rtabmap::getWMSize() const
{
if(_memory)
{
return (int)_memory->getWorkingMem().size()-1; // remove virtual place
}
return 0;
}
std::map<int, int> Rtabmap::getWeights() const
{
std::map<int, int> weights;
if(_memory)
{
weights = _memory->getWeights();
weights.erase(-1);// Ignore the virtual signature (if here)
}
return weights;
}
std::set<int> Rtabmap::getSTM() const
{
if(_memory)
{
return _memory->getStMem();
}
return std::set<int>();
}
int Rtabmap::getSTMSize() const
{
if(_memory)
{
return (int)_memory->getStMem().size();
}
return 0;
}
int Rtabmap::getTotalMemSize() const
{
if(_memory)
{
const Signature * s =_memory->getLastWorkingSignature();
if(s)
{
return s->id();
}
}
return 0;
}
std::multimap<int, cv::KeyPoint> Rtabmap::getWords(int locationId) const
{
if(_memory)
{
const Signature * s = _memory->getSignature(locationId);
if(s)
{
return s->getWords();
}
}
return std::multimap<int, cv::KeyPoint>();
}
bool Rtabmap::isInSTM(int locationId) const
{
if(_memory)
{
return _memory->isInSTM(locationId);
}
return false;
}
bool Rtabmap::isIDsGenerated() const
{
if(_memory)
{
return _memory->isIDsGenerated();
}
return Parameters::defaultMemGenerateIds();
}
const Statistics & Rtabmap::getStatistics() const
{
return statistics_;
}
/*
bool Rtabmap::getMetricData(int locationId, cv::Mat & rgb, cv::Mat & depth, float & depthConstant, Transform & pose, Transform & localTransform) const
{
if(_memory)
{
const Signature * s = _memory->getSignature(locationId);
if(s && _optimizedPoses.find(s->id()) != _optimizedPoses.end())
{
rgb = s->getImage();
depth = s->getDepth();
depthConstant = s->getDepthConstant();
pose = _optimizedPoses.at(s->id());
localTransform = s->getLocalTransform();
return true;
}
}
return false;
}
*/
Transform Rtabmap::getPose(int locationId) const
{
if(_memory)
{
const Signature * s = _memory->getSignature(locationId);
if(s && _optimizedPoses.find(s->id()) != _optimizedPoses.end())
{
return _optimizedPoses.at(s->id());
}
}
return Transform();
}
int Rtabmap::triggerNewMap()
{
int mapId = -1;
if(_memory)
{
std::map<int, int> reducedIds;
mapId = _memory->incrementMapId(&reducedIds);
UINFO("New map triggered, new map = %d", mapId);
_optimizedPoses.clear();
_constraints.clear();
_lastLocalizationNodeId = 0;
//Verify if there are nodes that were merged through graph reduction
if(reducedIds.size() && _path.size())
{
for(unsigned int i=0; i<_path.size(); ++i)
{
std::map<int, int>::const_iterator iter = reducedIds.find(_path[i].first);
if(iter!= reducedIds.end())
{
// change path ID to loop closure ID
_path[i].first = iter->second;
}
}
}
}
return mapId;
}
bool Rtabmap::labelLocation(int id, const std::string & label)
{
if(_memory)
{
if(id > 0)
{
return _memory->labelSignature(id, label);
}
else if(_memory->getLastWorkingSignature())
{
return _memory->labelSignature(_memory->getLastWorkingSignature()->id(), label);
}
else
{
UERROR("Last signature is null! Cannot set label \"%s\"", label.c_str());
}
}
return false;
}
bool Rtabmap::setUserData(int id, const cv::Mat & data)
{
if(_memory)
{
if(id > 0)
{
return _memory->setUserData(id, data);
}
else if(_memory->getLastWorkingSignature())
{
return _memory->setUserData(_memory->getLastWorkingSignature()->id(), data);
}
else
{
UERROR("Last signature is null! Cannot set user data!");
}
}
return false;
}
void Rtabmap::generateDOTGraph(const std::string & path, int id, int margin)
{
if(_memory)
{
_memory->joinTrashThread(); // make sure the trash is flushed
if(id > 0)
{
std::map<int, int> ids = _memory->getNeighborsId(id, margin, -1, false);
if(ids.size() > 0)
{
ids.insert(std::pair<int,int>(id, 0));
std::set<int> idsSet;
for(std::map<int, int>::iterator iter = ids.begin(); iter!=ids.end(); ++iter)
{
idsSet.insert(idsSet.end(), iter->first);
}
_memory->generateGraph(path, idsSet);
}
else
{
UERROR("No neighbors found for signature %d.", id);
}
}
else
{
_memory->generateGraph(path);
}
}
}
void Rtabmap::exportPoses(const std::string & path, bool optimized, bool global, int format)
{
if(_memory && _memory->getLastWorkingSignature())
{
std::map<int, Transform> poses;
std::multimap<int, Link> constraints;
if(optimized)
{
this->optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), global, poses, &constraints);
}
else
{
std::map<int, int> ids = _memory->getNeighborsId(_memory->getLastWorkingSignature()->id(), 0, global?-1:0, true);
_memory->getMetricConstraints(uKeysSet(ids), poses, constraints, global);
}
std::map<int, double> stamps;
if(format == 1)
{
for(std::map<int, Transform>::iterator iter=poses.begin(); iter!=poses.end(); ++iter)
{
Transform o;
int m, w;
std::string l;
double stamp = 0.0;
_memory->getNodeInfo(iter->first, o, m, w, l, stamp, true);
stamps.insert(std::make_pair(iter->first, stamp));
}
}
graph::exportPoses(path, format, poses, constraints, stamps);
}
}
void Rtabmap::resetMemory()
{
_highestHypothesis = std::make_pair(0,0.0f);
_loopClosureHypothesis = std::make_pair(0,0.0f);
_lastProcessTime = 0.0;
_someNodesHaveBeenTransferred = false;
_optimizedPoses.clear();
_constraints.clear();
_mapCorrection.setIdentity();
_lastLocalizationPose.setNull();
_lastLocalizationNodeId = 0;
_distanceTravelled = 0.0f;
this->clearPath(0);
if(_memory)
{
_memory->init(_databasePath, true, _modifiedParameters, true);
if(_memory->getLastWorkingSignature())
{
optimizeCurrentMap(_memory->getLastWorkingSignature()->id(), false, _optimizedPoses, &_constraints);
}
if(_bayesFilter)
{
_bayesFilter->reset();
}
}
else
{
UERROR("RTAB-Map is not initialized. No memory to reset...");
}
this->setupLogFiles(true);
}
//============================================================
// MAIN LOOP
//============================================================
bool Rtabmap::process(
const SensorData & data,
const Transform & odomPose,
const cv::Mat & covariance)
{
UDEBUG("");
//============================================================
// Initialization
//============================================================
UTimer timer;
UTimer timerTotal;
double timeMemoryUpdate = 0;
double timeScanMatching = 0;
double timeLocalTimeDetection = 0;
double timeLocalSpaceDetection = 0;
double timeCleaningNeighbors = 0;
double timeReactivations = 0;
double timeAddLoopClosureLink = 0;
double timeMapOptimization = 0;
double timeRetrievalDbAccess = 0;
double timeLikelihoodCalculation = 0;
double timePosteriorCalculation = 0;
double timeHypothesesCreation = 0;
double timeHypothesesValidation = 0;
double timeRealTimeLimitReachedProcess = 0;
double timeMemoryCleanup = 0;
double timeEmptyingTrash = 0;
double timeJoiningTrash = 0;
double timeStatsCreation = 0;
float hypothesisRatio = 0.0f; // Only used for statistics
bool rejectedHypothesis = false;
std::map<int, float> rawLikelihood;
std::map<int, float> adjustedLikelihood;
std::map<int, float> likelihood;
std::map<int, int> weights;
std::map<int, float> posterior;
std::list<std::pair<int, float> > reactivateHypotheses;
std::map<int, int> childCount;
std::set<int> signaturesRetrieved;
int localLoopClosuresInTimeFound = 0;
const Signature * signature = 0;
const Signature * sLoop = 0;
_loopClosureHypothesis = std::make_pair(0,0.0f);
std::pair<int, float> lastHighestHypothesis = _highestHypothesis;
_highestHypothesis = std::make_pair(0,0.0f);
std::set<int> immunizedLocations;
statistics_ = Statistics(); // reset
//============================================================
// Wait for an image...
//============================================================
ULOGGER_INFO("getting data...");
timer.start();
timerTotal.start();
UASSERT_MSG(_memory, "RTAB-Map is not initialized!");
UASSERT_MSG(_bayesFilter, "RTAB-Map is not initialized!");
UASSERT_MSG(_graphOptimizer, "RTAB-Map is not initialized!");
//============================================================
// If RGBD SLAM is enabled, a pose must be set.
//============================================================
if(_rgbdSlamMode)
{
if(odomPose.isNull())
{
UERROR("RGB-D SLAM mode is enabled and no odometry is provided. "
"Image %d is ignored!", data.id());
return false;
}
else
{
// Detect if the odometry is reset. If yes, trigger a new map.
if(_memory->getLastWorkingSignature())
{
const Transform & lastPose = _memory->getLastWorkingSignature()->getPose(); // use raw odometry
// look for identity
if(!lastPose.isIdentity() && odomPose.isIdentity())
{
int mapId = triggerNewMap();
UWARN("Odometry is reset (identity pose detected). Increment map id to %d!", mapId);
}
else if(_newMapOdomChangeDistance > 0.0)
{
// look for large change
Transform lastPoseToNewPose = lastPose.inverse() * odomPose;
float x,y,z, roll,pitch,yaw;
lastPoseToNewPose.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
if((x*x + y*y + z*z) > _newMapOdomChangeDistance*_newMapOdomChangeDistance)
{
int mapId = triggerNewMap();
UWARN("Odometry is reset (large odometry change detected > %f). A new map (%d) is created! Last pose = %s, new pose = %s",
_newMapOdomChangeDistance,
mapId,
lastPose.prettyPrint().c_str(),
odomPose.prettyPrint().c_str());
}
}
}
}
}
//============================================================
// Memory Update : Location creation + Add to STM + Weight Update (Rehearsal)
//============================================================
ULOGGER_INFO("Updating memory...");
if(_rgbdSlamMode)
{
if(!_memory->update(data, odomPose, covariance, &statistics_))
{
return false;
}
}
else
{
if(!_memory->update(data, Transform(), cv::Mat(), &statistics_))
{
return false;
}
}
signature = _memory->getLastWorkingSignature();
if(!signature)
{
UFATAL("Not supposed to be here...last signature is null?!?");
}
ULOGGER_INFO("Processing signature %d w=%d", signature->id(), signature->getWeight());
timeMemoryUpdate = timer.ticks();
ULOGGER_INFO("timeMemoryUpdate=%fs", timeMemoryUpdate);
//============================================================
// Metric
//============================================================
bool smallDisplacement = false;
std::list<int> signaturesRemoved;
if(_rgbdSlamMode)
{
//Verify if there was a rehearsal
int rehearsedId = (int)uValue(statistics_.data(), Statistics::kMemoryRehearsal_merged(), 0.0f);
if(rehearsedId > 0)
{
_optimizedPoses.erase(rehearsedId);
}
else if(signature->getWeight() >= 0 && _rgbdLinearUpdate > 0.0f && _rgbdAngularUpdate > 0.0f)
{
//============================================================
// Minimum displacement required to add to Memory
//============================================================
const std::map<int, Link> & links = signature->getLinks();
if(links.size() == 1)
{
// don't do this if there are intermediate nodes
const Signature * s = _memory->getSignature(links.begin()->second.to());
UASSERT(s!=0);
if(s->getWeight() >= 0)
{
float x,y,z, roll,pitch,yaw;
links.begin()->second.transform().getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
bool isMoving = fabs(x) > _rgbdLinearUpdate ||
fabs(y) > _rgbdLinearUpdate ||
fabs(z) > _rgbdLinearUpdate ||
fabs(roll) > _rgbdAngularUpdate ||