-
Notifications
You must be signed in to change notification settings - Fork 3
/
MainWindow.cpp
executable file
·1616 lines (1257 loc) · 53 KB
/
MainWindow.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
#include "MainWindow.hpp"
//#include "/usr/include/x86_64-linux-gnu/qt5/QtGui/qguiapplication.h"
//#include "/home/muhammad/Desktop/MRPT/samples/build-qt_integration-Desktop-Default/ui_MainWindow.h"
//#include "../build-mrptQt-Desktop_Qt_5_10_0_GCC_64bit-Debug/ui_MainWindow.h"
#include "../build-mrptQt-Desktop_Qt_5_10_0_GCC_64bit-Debug/ui_MainWindow.h"
//#include <qt5/QtGui/QGuiApplication>
#include "QtGL.hpp"
#include <mrpt/gui/about_box.h>
#include "DEFAULT_GRIDMAP_DATA.h"
#include <mrpt/nav.h>
#include <mrpt/gui.h>
#include <mrpt/opengl.h>
#include <mrpt/system/filesystem.h>
#include <QDebug>
MainWindow::MainWindow(QWidget *parent) :
QMainWindow(parent),
ui(new Ui::MainWindow),
m_gridMap(),
m_targetPoint(-5, -7),
m_robotPose(0, 0, 0),
m_curCursorPos(0, 0),
m_cursorPickState(cpsNone)
{
ui->setupUi(this);
ui->statusBar->showMessage("Ready");
ui->statusBar->setToolTip("Click the open button to open a gridmap file");
ui->centralWidget->installEventFilter(this);
ui->actionExit->setShortcut(Qt::Key_F4 | Qt::Key_Alt);
ui->actionFull_Screen->setShortcut(Qt::Key_F11);
ui->actionHelp->setShortcut(Qt::Key_F1);
ui->actionOpen->setShortcut(Qt::Key_O | Qt::CTRL);
ui->actionCapture_Image->setShortcut(Qt::Key_I | Qt::CTRL);
ui->actionProperty_Editor->setShortcut(Qt::Key_P | Qt::CTRL);
ui->centralWidget->setMouseTracking(true);
this->setMouseTracking(true);
timRunSimul = new QTimer(this);
connect(timRunSimul, SIGNAL(timeout()), this, SLOT(OntimRunSimulTrigger()));
}
MainWindow::~MainWindow()
{
delete ui;
}
// ------------------------------------------------------
// UI init and some
// ------------------------------------------------------
void MainWindow::on_actionOpen_triggered()
{
QString name = QFileDialog::getOpenFileName(this, "Select gridmap file",tr("All files (*.*);;GRIDMAP(*.gridmap)") ,"GRIDMAP (*.gridmap)");
if(name.isEmpty()){
return;
}
openFile(name);
}
void MainWindow::openFile(QString filename){
COccupancyGridMap2D gridmap;
CFileGZInputStream in_s(filename.toStdString());
in_s >> gridmap;
CSetOfObjects::Ptr gl_grid;
if (!gl_grid)
gl_grid = CSetOfObjects::Create();
gl_grid->clear();
gridmap.getAs3DObject(gl_grid);
gl_grid->setName("gridmap");
opengl::CRenderizable::Ptr obj =QtGL::theScene.getByName("gridmap");
if(obj != NULL){
QtGL::theScene.removeObject(obj);
}
QtGL::theScene.insert(gl_grid);
// ui->widget->setRender(true);
ui->statusBar->showMessage(filename);
}
void MainWindow::on_actionExit_triggered()
{
QCoreApplication::quit();
}
bool MainWindow::eventFilter(QObject *target, QEvent *event) {
if (event->type() == QEvent::KeyRelease) {
QKeyEvent *keyEvent = static_cast<QKeyEvent *>(event);
if(keyEvent->key() == Qt::Key_Escape){
normalScreen();
}
return QObject::eventFilter(target, event);
}
}
void MainWindow::on_actionFull_Screen_triggered()
{
std::system("notify-send 'MRPT - Gridmap visualizer' 'Please use escape to exit fullscreen'");
this->showFullScreen();
ui->toolBar->hide();
ui->statusBar->hide();
}
void MainWindow::normalScreen(){
this->showNormal();
ui->toolBar->show();
ui->statusBar->show();
this->showMaximized();
}
void MainWindow::on_actionHelp_triggered()
{
HelpDialog dialog(this);
dialog.setWindowTitle("Help");
dialog.exec();
}
void MainWindow::on_actionProperty_Editor_triggered()
{
PropertyEditor dialog(this);
dialog.setWindowTitle("Property Editor");
dialog.exec();
}
void MainWindow::on_actionCapture_Image_triggered()
{
// QtGL* w = ui->centralWidget->findChild<QtGL*>("widget");
// QScreen *screen = QGuiApplication::primaryScreen();
// //QScreen *screen1 = QGuiApplication::primaryScreen();
// QPixmap pixmap;
// if (screen){
// pixmap = screen->grabWindow(w->winId());
// //pixmap = screen->pixmapDataFactory();
// }
// QApplication::clipboard()->setPixmap(pixmap);
QMessageBox::information(this,"Capture image", "Successfully copied the image to the clipboard!");
}
void MainWindow::keyPressEvent(QKeyEvent *event){
if(event->key() == Qt::Key_Right){
}
if(event->key() == Qt::Key_Left){
}
if(event->key() == Qt::Key_Up){
}
if(event->key() == Qt::Key_Down){
}
if(event->key() == Qt::Key_R){
}
if(event->key() == Qt::Key_T){
}
}
void MainWindow::mouseMoveEvent(QMouseEvent *event){
QPoint currentPos = event->pos();
/*float x = -mousePosition.x() + currentPos.x();
float y = -mousePosition.y() + currentPos.y();
if(event->buttons() == Qt::LeftButton){
if(x > 0){
}
else{
}
}
if(event->buttons() == Qt::RightButton){
if(y > 0){
}
else{
}
}*/
int X, Y;
X = currentPos.x();
Y = currentPos.y();
qDebug("nav target point currentPos X=%.03f Y=%.04f Z=0", currentPos.x(), currentPos.y());
qDebug("QtGL currentPos X=%.03f Y=%.04f Z=0", ui->widget->getMousePosition().x(), ui->widget->getMousePosition().y());
// Intersection of 3D ray with ground plane ====================
TLine3D ray;
QtGL::theScene.getViewport()->get3DRayForPixelCoord( X, Y, ray);
// Create a 3D plane, e.g. Z=0
const TPlane ground_plane(
TPoint3D(0, 0, 0), TPoint3D(1, 0, 0), TPoint3D(0, 1, 0));
// Intersection of the line with the plane:
TObject3D inters;
intersect(ray, ground_plane, inters);
// Interpret the intersection as a point, if there is an intersection:
TPoint3D inters_pt;
if (inters.getPoint(inters_pt))
{
m_curCursorPos.x = inters_pt.x;
m_curCursorPos.y = inters_pt.y;
qDebug("nav target point X=%.03f Y=%.04f Z=0", inters_pt.x, inters_pt.y);
if (m_cursorPickState == cpsPickTarget)
{
m_gl_placing_nav_target->setVisibility(true);
m_gl_placing_nav_target->setLocation(
m_curCursorPos.x, m_curCursorPos.y, 0.05);
qDebug("nav target point X=%.03f Y=%.04f Z=0", m_curCursorPos.x, m_curCursorPos.y);
}
else if (m_cursorPickState == cpsPlaceRobot)
{
m_gl_placing_robot->setVisibility(true);
m_gl_placing_robot->setLocation(
m_curCursorPos.x, m_curCursorPos.y, 0.05);
qDebug("nav robot point X=%.03f Y=%.04f Z=0", m_curCursorPos.x, m_curCursorPos.y);
}
// qDebug("X=%.03f Y=%.04f Z=0", m_curCursorPos.x, m_curCursorPos.y);
}
}
void MainWindow::mousePressEvent(QMouseEvent *event){
switch (m_cursorPickState)
{
case cpsPickTarget:
{
m_targetPoint = m_curCursorPos;
ui->btnNavEndPoint->setEnabled(false);
ui->btnNavEndPoint->update();
m_gl_placing_nav_target->setVisibility(false);
qDebug("place the robot target point : %.03f %.03f",m_targetPoint.x,m_targetPoint.y);
break;
}
case cpsPlaceRobot:
{
m_robotPose.x = m_curCursorPos.x;
m_robotPose.y = m_curCursorPos.y;
ui->btnNavStartPoint->setEnabled(false);
ui->btnNavStartPoint->update();
m_gl_placing_robot->setVisibility(false);
qDebug("place the robot start point : %.03f %.03f",m_targetPoint.x,m_targetPoint.y);
break;
}
default:
break;
}
ui->widget->setCursor(Qt::ArrowCursor);
//m_plot3D->SetCursor(*wxSTANDARD_CURSOR); // End of cross cursor
m_cursorPickState = cpsNone; // end of mode
}
void MainWindow::on_btnTest_clicked()
{
std::cout<< "on_btnTest_clicked"<<std::endl;
}
// ------------------------------------------------------
// RBPF-SLAM MapBuilding RBPF
// ------------------------------------------------------
/**
* rbpf-slam 参数设置
* @brief MainWindow::initMapBuildingParams
*/
void MainWindow::initMapBuildingParams(){
qDebug()<<"移动机器人同步建图与导航V1.0 \n";
qDebug()<< " MRPT C++ Library: "<<MRPT_getVersion().c_str() << "- Sources timestamp: " << MRPT_getCompilationDate().c_str();
std::string intConfigFileName = string("/usr/share/mrpt/config_files/rbpf-slam/gridmapping_RBPF_grid_ICPbased_malaga.ini");
//std::string intConfigFileName = string("/home/sl/projects/Qt/gridmapping_RBPF_grid_ICPbased_malaga.ini");
INI_FILENAME = std::string(intConfigFileName);
ASSERT_FILE_EXISTS_(INI_FILENAME)
string override_rawlog_file;
override_rawlog_file = string("/usr/share/mrpt/datasets/2006-01ENE-21-SENA_Telecom Faculty_one_loop_only.rawlog");
CConfigFile iniFile(INI_FILENAME);
// ------------------------------------------
// Load config from file:
// ------------------------------------------
RAWLOG_FILE = !override_rawlog_file.empty()
? override_rawlog_file
: iniFile.read_string(
"MappingApplication", "rawlog_file", "",
/*Force existence:*/ true);
rawlog_offset =
iniFile.read_int("MappingApplication", "rawlog_offset", 0);
OUT_DIR_STD = iniFile.read_string(
"MappingApplication", "logOutput_dir", "log_out",
/*Force existence:*/ true);
LOG_FREQUENCY = iniFile.read_int(
"MappingApplication", "LOG_FREQUENCY", 5,
/*Force existence:*/ true);
GENERATE_LOG_JOINT_H = iniFile.read_bool(
"MappingApplication", "GENERATE_LOG_JOINT_H", false);
GENERATE_LOG_INFO =
iniFile.read_bool("MappingApplication", "GENERATE_LOG_INFO", false);
SAVE_POSE_LOG =
iniFile.read_bool("MappingApplication", "SAVE_POSE_LOG", false);
SAVE_MAP_IMAGES =
iniFile.read_bool("MappingApplication", "SAVE_MAP_IMAGES", false);
SAVE_3D_SCENE =
iniFile.read_bool("MappingApplication", "SAVE_3D_SCENE", false);
CAMERA_3DSCENE_FOLLOWS_ROBOT = iniFile.read_bool(
"MappingApplication", "CAMERA_3DSCENE_FOLLOWS_ROBOT", true);
SHOW_PROGRESS_IN_WINDOW = iniFile.read_bool(
"MappingApplication", "SHOW_PROGRESS_IN_WINDOW", false);
SHOW_PROGRESS_IN_WINDOW_DELAY_MS = iniFile.read_int(
"MappingApplication", "SHOW_PROGRESS_IN_WINDOW_DELAY_MS", 1);
METRIC_MAP_CONTINUATION_GRIDMAP_FILE = iniFile.read_string(
"MappingApplication", "METRIC_MAP_CONTINUATION_GRIDMAP_FILE", "");
MRPT_LOAD_CONFIG_VAR(
SIMPLEMAP_CONTINUATION, string, iniFile, "MappingApplication");
METRIC_MAP_CONTINUATION_START_POSE.x = iniFile.read_double(
"MappingApplication", "METRIC_MAP_CONTINUATION_START_POSE_X", .0);
METRIC_MAP_CONTINUATION_START_POSE.y = iniFile.read_double(
"MappingApplication", "METRIC_MAP_CONTINUATION_START_POSE_Y", .0);
METRIC_MAP_CONTINUATION_START_POSE.phi = DEG2RAD(
iniFile.read_double(
"MappingApplication",
"METRIC_MAP_CONTINUATION_START_POSE_PHI_DEG", .0));
MRPT_LOAD_CONFIG_VAR(
PROGRESS_WINDOW_WIDTH, int, iniFile, "MappingApplication");
MRPT_LOAD_CONFIG_VAR(
PROGRESS_WINDOW_HEIGHT, int, iniFile, "MappingApplication");
// easier!
OUT_DIR = OUT_DIR_STD.c_str();
// Print params:
qDebug("Running with the following parameters:\n");
qDebug(" RAWLOG file:'%s'\n", RAWLOG_FILE.c_str());
qDebug(" Output directory:\t\t\t'%s'\n", OUT_DIR);
qDebug(" Log record freq:\t\t\t%u\n", LOG_FREQUENCY);
qDebug(" GENERATE_LOG_JOINT_H:\t\t\t%c\n", GENERATE_LOG_JOINT_H ? 'Y' : 'N');
qDebug(" GENERATE_LOG_INFO:\t\t\t%c\n", GENERATE_LOG_INFO ? 'Y' : 'N');
qDebug(" SAVE_MAP_IMAGES:\t\t\t%c\n", SAVE_MAP_IMAGES ? 'Y' : 'N');
qDebug(" SAVE_3D_SCENE:\t\t\t%c\n", SAVE_3D_SCENE ? 'Y' : 'N');
qDebug(" SAVE_POSE_LOG:\t\t\t%c\n", SAVE_POSE_LOG ? 'Y' : 'N');
qDebug( " CAMERA_3DSCENE_FOLLOWS_ROBOT:\t%c\n", CAMERA_3DSCENE_FOLLOWS_ROBOT ? 'Y' : 'N');
qDebug( " SHOW_PROGRESS_IN_WINDOW:\t%c\n",SHOW_PROGRESS_IN_WINDOW ? 'Y' : 'N');
// Checks:
ASSERT_(RAWLOG_FILE.size() > 0);
ASSERT_FILE_EXISTS_(RAWLOG_FILE)
// Set relative path for externally-stored images in rawlogs:
string rawlog_images_path = extractFileDirectory(RAWLOG_FILE);
rawlog_images_path += "/Images";
CImage::setImagesPathBase(rawlog_images_path); // Set it.
// Run:qDebug
// MapBuilding_RBPF();
}
// MapBuilding RBPF
void MainWindow::MapBuilding_RBPF()
{
qDebug()<<"Build map ";
MRPT_START
CTicTac tictac, tictacGlobal, tictac_JH;
int step = 0;
CSimpleMap finalMap;
float t_exec;
COccupancyGridMap2D::TEntropyInfo entropy;
char strFil[1000];
size_t rawlogEntry = 0;
CFileGZInputStream rawlogFile(RAWLOG_FILE);
// ---------------------------------
// MapPDF opts
// ---------------------------------
CMetricMapBuilderRBPF::TConstructionOptions rbpfMappingOptions;
rbpfMappingOptions.loadFromConfigFile(
CConfigFile(INI_FILENAME), "MappingApplication");
rbpfMappingOptions.dumpToConsole();
// ---------------------------------
// Constructor
// ---------------------------------
CMetricMapBuilderRBPF mapBuilder(rbpfMappingOptions);
// handle the case of metric map continuation
if (!METRIC_MAP_CONTINUATION_GRIDMAP_FILE.empty())
{
CSimpleMap dummySimpleMap;
CPosePDFGaussian startPose;
startPose.mean.x(METRIC_MAP_CONTINUATION_START_POSE.x);
startPose.mean.y(METRIC_MAP_CONTINUATION_START_POSE.y);
startPose.mean.phi(METRIC_MAP_CONTINUATION_START_POSE.phi);
startPose.cov.setZero();
mrpt::maps::COccupancyGridMap2D gridmap;
{
mrpt::utils::CFileGZInputStream f(
METRIC_MAP_CONTINUATION_GRIDMAP_FILE);
f >> gridmap;
}
mapBuilder.initialize(dummySimpleMap, &startPose);
for (CMultiMetricMapPDF::CParticleList::iterator it =
mapBuilder.mapPDF.m_particles.begin();
it != mapBuilder.mapPDF.m_particles.end(); ++it)
{
CRBPFParticleData* part_d = it->d.get();
CMultiMetricMap& mmap = part_d->mapTillNow;
mrpt::maps::COccupancyGridMap2D::Ptr it_grid =
mmap.getMapByClass<mrpt::maps::COccupancyGridMap2D>();
ASSERTMSG_(
it_grid,
"No gridmap in multimetric map definition, but metric map "
"continuation was set (!)");
it_grid->copyMapContentFrom(gridmap);
}
}
if (!SIMPLEMAP_CONTINUATION.empty())
{
mrpt::maps::CSimpleMap init_map;
mrpt::utils::CFileGZInputStream(SIMPLEMAP_CONTINUATION) >> init_map;
mapBuilder.initialize(init_map);
}
// ---------------------------------
// CMetricMapBuilder::TOptions
// ---------------------------------
// mapBuilder.setVerbosityLevel( mrpt::utils::LVL_DEBUG ); // default
// value: as loaded from config file
mapBuilder.options.enableMapUpdating = true;
mapBuilder.options.debugForceInsertion = false;
getRandomGenerator().randomize();
// Prepare output directory:
// --------------------------------
// os::sprintf(strFil,1000,"%s/*.*",OUT_DIR);
deleteFilesInDirectory(OUT_DIR);
createDirectory(OUT_DIR);
string OUT_DIR_MAPS = format("%s/maps", OUT_DIR);
string OUT_DIR_3D = format("%s/3D", OUT_DIR);
deleteFilesInDirectory(OUT_DIR_MAPS);
createDirectory(OUT_DIR_MAPS);
deleteFilesInDirectory(OUT_DIR_3D);
createDirectory(OUT_DIR_3D);
// Open log files:
// ----------------------------------
CFileOutputStream f_log(format("%s/log_times.txt", OUT_DIR));
CFileOutputStream f_info(format("%s/log_info.txt", OUT_DIR));
CFileOutputStream f_jinfo(format("%s/log_jinfo.txt", OUT_DIR));
CFileOutputStream f_path(format("%s/log_estimated_path.txt", OUT_DIR));
CFileOutputStream f_pathOdo(format("%s/log_odometry_path.txt", OUT_DIR));
CFileOutputStream f_partStats(format("%s/log_ParticlesStats.txt", OUT_DIR));
f_log.printf(
"%% time_step execution_time(ms) map_size(#frames) frame_inserted? "
"\n"
"%%-------------------------------------------------------------------"
"\n");
f_info.printf(
"%% EMI H EMMI effecMappedArea effecMappedCells \n"
"%%-------------------------------------------------------\n");
f_pathOdo.printf(
"%% time_step x y z yaw pitch roll timestamp \n"
"%%--------------------------------------------\n");
f_pathOdo.printf(
"%% time_step x y z yaw pitch roll \n"
"%%----------------------------------\n");
f_partStats.printf(
"%% time_step #particles ESS \n"
"%%------------------------------\n");
// ----------------------------------------------------------
// Map Building
// ----------------------------------------------------------
CActionCollection::Ptr action ;
CSensoryFrame::Ptr observations ;
//std::deque<CObservationGasSensors::Ptr> gasObservations =nullptr;
//std::deque<CObservationWirelessPower::Ptr> wifiObservations = nullptr;
CPose3D odoPose(0, 0, 0);
// mrpt::gui:: CDisplayWindow3D win3D("RBPF-SLAM @ MRPT C++ Library", PROGRESS_WINDOW_WIDTH, PROGRESS_WINDOW_HEIGHT);
// win3D.setCameraZoom(40);
// win3D.setCameraAzimuthDeg(-50);
// win3D.setCameraElevationDeg(70);
// if (SHOW_PROGRESS_IN_WINDOW)
// {
// win3D = new CDisplayWindow3D(
// "RBPF-SLAM @ MRPT C++ Library", PROGRESS_WINDOW_WIDTH,
// PROGRESS_WINDOW_HEIGHT);
// win3D.setCameraZoom(40);
// win3D.setCameraAzimuthDeg(-50);
// win3D.setCameraElevationDeg(70);
// }
tictacGlobal.Tic();
for (;;)
{
if (os::kbhit())
{
char c = os::getch();
if (c == 27) break;
}
// Load action/observation pair from the rawlog:
// --------------------------------------------------
if (!CRawlog::readActionObservationPair(
rawlogFile, action, observations, rawlogEntry))
break; // file EOF
if (rawlogEntry >= rawlog_offset)
{
// Update odometry:
{
CActionRobotMovement2D::Ptr act =
action->getBestMovementEstimation();
if (act)
odoPose = odoPose + CPose3D(act->poseChange->getMeanVal());
else
{
CActionRobotMovement3D::Ptr act3D =
action->getActionByClass<CActionRobotMovement3D>();
if (act3D) odoPose = odoPose + act3D->poseChange.mean;
}
}
double observations_timestamp_double = 0;
if (observations && observations->size() > 0)
observations_timestamp_double = mrpt::system::timestampTotime_t(
(*observations->begin())->timestamp);
// Execute:
// ----------------------------------------
tictac.Tic();
mapBuilder.processActionObservation(*action, *observations);
t_exec = tictac.Tac();
qDebug("Map building executed in %.03fms\n", 1000.0f * t_exec);
// Info log:
// -----------
f_log.printf(
"%u %f %i %i\n", static_cast<unsigned int>(step),
1000.0f * t_exec, mapBuilder.getCurrentlyBuiltMapSize(),
mapBuilder.m_statsLastIteration.observationsInserted ? int(1)
: int(0));
CPose3DPDF::Ptr curPDFptr = mapBuilder.getCurrentPoseEstimation();
CPose3DPDFParticles curPDF;
if (IS_CLASS(curPDFptr, CPose3DPDFParticles))
{
CPose3DPDFParticles::Ptr pp =
std::dynamic_pointer_cast<CPose3DPDFParticles>(curPDFptr);
curPDF = *pp;
}
if (0 == (step % LOG_FREQUENCY))
{
const CMultiMetricMap* mostLikMap =
mapBuilder.mapPDF.getCurrentMostLikelyMetricMap();
if (GENERATE_LOG_INFO)
{
qDebug("Saving info log information...");
tictac_JH.Tic();
const CMultiMetricMap* avrMap =
mapBuilder.mapPDF.getAveragedMetricMapEstimation();
ASSERT_(avrMap->m_gridMaps.size() > 0);
COccupancyGridMap2D::Ptr grid = avrMap->m_gridMaps[0];
grid->computeEntropy(entropy);
grid->saveAsBitmapFile(
format("%s/EMMI_gridmap_%03u.bmp", OUT_DIR, step));
f_info.printf(
"%f %f %f %f %lu\n", entropy.I, entropy.H,
entropy.mean_I, entropy.effectiveMappedArea,
entropy.effectiveMappedCells);
qDebug(
"Ok\n EMI = %.04f EMMI=%.04f (in %.03fms)\n",
entropy.I, entropy.mean_I, 1000.0f * tictac_JH.Tac());
}
// Pose log:
// -------------
if (SAVE_POSE_LOG)
{
qDebug("Saving pose log information...");
curPDF.saveToTextFile(
format("%s/mapbuild_posepdf_%03u.txt", OUT_DIR, step));
qDebug("Ok\n");
}
// Map images:
// -------------
if (SAVE_MAP_IMAGES)
{
qDebug("Saving map images to files...");
// Most likely maps:
// ----------------------------------------
mostLikMap->saveMetricMapRepresentationToFile(
format(
"%s/mapbuilt_%05u_", OUT_DIR_MAPS.c_str(), step));
if (mostLikMap->m_gridMaps.size() > 0)
{
CImage img;
mapBuilder.drawCurrentEstimationToImage(&img);
img.saveToFile(
format("%s/mapping_%05u.png", OUT_DIR, step));
}
qDebug("Ok!\n");
}
// Save a 3D scene view of the mapping process:
COpenGLScene::Ptr scene;
if (SAVE_3D_SCENE || SHOW_PROGRESS_IN_WINDOW)
{
scene = mrpt::make_aligned_shared<COpenGLScene>();
// The ground:
mrpt::opengl::CGridPlaneXY::Ptr groundPlane =
mrpt::make_aligned_shared<mrpt::opengl::CGridPlaneXY>(
-500, 500, -500, 500, 0, 1); //-150,150,-150,150,0,1)
groundPlane->setColor(0.4, 0.4, 0.4);
scene->insert(groundPlane);
// The camera pointing to the current robot pose:
if (CAMERA_3DSCENE_FOLLOWS_ROBOT)
{
mrpt::opengl::CCamera::Ptr objCam =
mrpt::make_aligned_shared<mrpt::opengl::CCamera>();
CPose3D robotPose;
curPDF.getMean(robotPose);
objCam->setPointingAt(robotPose);
//objCam->setAzimuthDegrees(-30);
//objCam->setElevationDegrees(10); //30
//objCam->setZoomDistance(15); // add by test
scene->insert(objCam);
}
// Draw the map(s):
mrpt::opengl::CSetOfObjects::Ptr objs =
mrpt::make_aligned_shared<
mrpt::opengl::CSetOfObjects>();
mostLikMap->getAs3DObject(objs);
scene->insert(objs);
// Draw the robot particles:
size_t M = mapBuilder.mapPDF.particlesCount();
mrpt::opengl::CSetOfLines::Ptr objLines =
mrpt::make_aligned_shared<mrpt::opengl::CSetOfLines>();
objLines->setColor(0, 1, 1);
for (size_t i = 0; i < M; i++)
{
std::deque<TPose3D> path;
mapBuilder.mapPDF.getPath(i, path);
float x0 = 0, y0 = 0, z0 = 0;
for (size_t k = 0; k < path.size(); k++)
{
objLines->appendLine(
x0, y0, z0 + 0.001, path[k].x, path[k].y,
path[k].z + 0.001);
x0 = path[k].x;
y0 = path[k].y;
z0 = path[k].z;
}
}
scene->insert(objLines);
// An ellipsoid:
CPose3D lastMeanPose;
float minDistBtwPoses = -1;
std::deque<TPose3D> dummyPath;
mapBuilder.mapPDF.getPath(0, dummyPath);
for (int k = (int)dummyPath.size() - 1; k >= 0; k--)
{
CPose3DPDFParticles poseParts;
mapBuilder.mapPDF.getEstimatedPosePDFAtTime(
k, poseParts);
CPose3D meanPose;
CMatrixDouble66 COV;
poseParts.getCovarianceAndMean(COV, meanPose);
if (meanPose.distanceTo(lastMeanPose) > minDistBtwPoses)
{
CMatrixDouble33 COV3 = COV.block(0, 0, 3, 3);
minDistBtwPoses = 6 * sqrt(COV3(0, 0) + COV3(1, 1));
opengl::CEllipsoid::Ptr objEllip =
mrpt::make_aligned_shared<opengl::CEllipsoid>();
objEllip->setLocation(
meanPose.x(), meanPose.y(),
meanPose.z() + 0.001);
objEllip->setCovMatrix(
COV3, COV3(2, 2) == 0 ? 2 : 3);
objEllip->setColor(0, 0, 1);
objEllip->enableDrawSolid3D(false);
scene->insert(objEllip);
lastMeanPose = meanPose;
}
}
} // end if show or save 3D scene->
if (SAVE_3D_SCENE)
{ // Save as file:
CFileGZOutputStream(
format(
"%s/buildingmap_%05u.3Dscene", OUT_DIR_3D.c_str(),
step))
<< *scene;
}
if (SHOW_PROGRESS_IN_WINDOW)
{
// QtGL::azimuth = 25.0f;
// QtGL::elevation = -15.0f;
// QtGL::distance= 5.0f;
// // QtGL::theScene.getViewPort()->getCamera().
// QtGL::theScene.getViewport()->getCamera().setAzimuthDegrees(QtGL::azimuth);
// QtGL::theScene.getViewport()->getCamera().setElevationDegrees(QtGL::elevation);
// QtGL::theScene.getViewport()->getCamera().setZoomDistance(QtGL::distance);
COpenGLScene tmpScene(*scene);
QtGL::theScene = tmpScene;
// QtGL::azimuth = 25.0f;
// QtGL::elevation = -15.0f;
// QtGL::distance= 35.0f;
ui->widget->updateScene();
// ui->widget->repaint();
//QtGL::updateScene();
// COpenGLScene::Ptr& scenePtr = win3D->get3DSceneAndLock();
// scenePtr = scene;
// win3D->unlockAccess3DScene();
// win3D->forceRepaint();
// int add_delay =
// SHOW_PROGRESS_IN_WINDOW_DELAY_MS - t_exec * 1000;
// if (add_delay > 0)
// std::this_thread::sleep_for(
// std::chrono::milliseconds(add_delay));
}
// Save the weighted entropy of each map:
// ----------------------------------------
if (GENERATE_LOG_JOINT_H)
{
qDebug("Saving joint H...");
tictac_JH.Tic();
double H_joint = mapBuilder.getCurrentJointEntropy();
double H_path =
mapBuilder.mapPDF.getCurrentEntropyOfPaths();
f_jinfo.printf("%e %e\n", H_joint, H_path);
qDebug(
"Ok\t joint-H=%f\t(in %.03fms)\n", H_joint,
1000.0f * tictac_JH.Tac());
}
} // end of LOG_FREQ
// Save the memory usage:
// ------------------------------------------------------------------
{
qDebug("Saving memory usage...");
unsigned long memUsage = getMemoryUsage();
FILE* f = os::fopen(
format("%s/log_MemoryUsage.txt", OUT_DIR).c_str(), "at");
if (f)
{
os::fprintf(f, "%u\t%lu\n", step, memUsage);
os::fclose(f);
}
qDebug("Ok! (%.04fMb)\n", ((float)memUsage) / (1024 * 1024));
}
// Save the parts stats:
f_partStats.printf(
"%u %u %f\n", (unsigned int)step, (unsigned int)curPDF.size(),
curPDF.ESS());
// Save the robot estimated pose for each step:
CPose3D meanPose;
mapBuilder.getCurrentPoseEstimation()->getMean(meanPose);
f_path.printf(
"%i %f %f %f %f %f %f %f\n", (int)rawlogEntry, meanPose.x(),
meanPose.y(), meanPose.z(), meanPose.yaw(), meanPose.pitch(),
meanPose.roll(), observations_timestamp_double);
f_pathOdo.printf(
"%i\t%f\t%f\t%f\t%f\t%f\t%f\n", step, odoPose.x(), odoPose.y(),
odoPose.z(), odoPose.yaw(), odoPose.pitch(), odoPose.roll());
} // end of if "rawlog_offset"...
step++;
qDebug(
"\n---------------- STEP %u | RAWLOG ENTRY %u ----------------\n",
step, (unsigned)rawlogEntry);
// Free memory:
action.reset();
observations.reset();
}; // end while
qDebug(
"\n---------------- END!! (total time: %.03f sec) ----------------\n",
tictacGlobal.Tac());
// Save map:
mapBuilder.getCurrentlyBuiltMap(finalMap);
CFileOutputStream filOut(format("%s/_finalmap_.simplemap", OUT_DIR));
filOut << finalMap;
// Save gridmap extend (if exists):
const CMultiMetricMap* mostLikMap =
mapBuilder.mapPDF.getCurrentMostLikelyMetricMap();
if (mostLikMap->m_gridMaps.size() > 0)
{
CMatrix auxMat(1, 4);
auxMat(0, 0) = mostLikMap->m_gridMaps[0]->getXMin();
auxMat(0, 1) = mostLikMap->m_gridMaps[0]->getXMax();
auxMat(0, 2) = mostLikMap->m_gridMaps[0]->getYMin();
auxMat(0, 3) = mostLikMap->m_gridMaps[0]->getYMax();
auxMat.saveToTextFile(
format("%s/finalGridmapSize.txt", OUT_DIR), MATRIX_FORMAT_FIXED);
}
// Save the most likely path of the particle set
FILE* f_pathPart;
os::sprintf(strFil, 1000, "%s/most_likely_path.txt", OUT_DIR);
f_pathPart = os::fopen(strFil, "wt");
ASSERT_(f_pathPart != nullptr);
std::deque<TPose3D> outPath;
std::deque<TPose3D>::iterator itPath;
mapBuilder.getCurrentMostLikelyPath(outPath);
for (itPath = outPath.begin(); itPath != outPath.end(); itPath++)
os::fprintf(
f_pathPart, "%.3f %.3f %.3f\n", itPath->x, itPath->y, itPath->yaw);
os::fclose(f_pathPart);
// Free gas readings memory (if any):
//gasObservations.clear();
// Free wifi readings memory (if any):
//wifiObservations.clear();
// Close 3D window, if any:
// if (win3D)
// {
// mrpt::system::pause();
// delete win3D;
// win3D = nullptr;
// }
MRPT_END
}
void MainWindow::on_btnSlamStart_clicked()
{
qDebug()<<" on_btnSlamStart_clicked debug";
ui->statusBar->showMessage( mrpt::format("重新开始创建地图... ")
.c_str());
initMapBuildingParams();
MapBuilding_RBPF();
}
void MainWindow::on_btnSlamEnd_clicked()
{
qDebug()<<"end build map ";
}
// ------------------------------------------------------
// Navigaion map
// ------------------------------------------------------
// ==== holonomic_navigator_demoFrame::TOptions ======
MainWindow::TOptions::TOptions()
: ROBOT_MAX_SPEED(4.0),
MAX_SENSOR_RADIUS(5.0),
SENSOR_NUM_RANGES(181),
SENSOR_RANGE_NOISE_STD(0.02)