-
Notifications
You must be signed in to change notification settings - Fork 19
/
Copy pathdemo_slam.cpp
1945 lines (1685 loc) · 75 KB
/
demo_slam.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
/**
* \file demo_slam.cpp
*
* ## Add brief description here ##
*
* \author [email protected]
* \date 28/04/2010
*
* ## Add a description here ##
*
* \ingroup rtslam
*/
/** ############################################################################
* #############################################################################
* features enable/disable
* ###########################################################################*/
/*
* STATUS: working fine, use it
* Ransac ensures that we use correct observations for a few first updates,
* allowing bad observations to be more easily detected by gating
* You can disable it by setting N_UPDATES_RANSAC to 0
*/
#define RANSAC_FIRST 1
/*
* STATUS: working fine, use it
* This allows to use Dala "atrv" robot model instead of camera (default) model in the Gdhe view display
*/
#define ATRV 0
/*
* STATUS: working fine, use it
* This allows to have 0% cpu used for waiting/idle
*/
//#define EVENT_BASED_RAW 1 // always enabled now
/*
* STATUS: in progress, do not use for now
* This allows to track landmarks longer by updating the reference patch when
* the landmark is not detected anymore and the point of view has changed
* significantly enough
* The problem is that the correlation is not robust enough in a matching
* (opposed to tracking) context, and it can provoke matching errors with a
* progressive appearance drift.
* Also decreasing perfs by 10%, probably because we save a view at each obs,
* or maybe it just because of the different random process
*/
//#define MULTIVIEW_DESCRIPTOR 1 // moved in config file
/*
* STATUS: in progress, do not use for now
* This allows to ignore some landmarks when we have some experience telling
* us that we can't observe this landmarks from here (masking), in order to
* save some time, and to allow creation of other observations in the
* neighborhood to keep localizing with enough landmarks.
* The problem is that sometimes it creates too many landmarks in the same area
* (significantly slowing down slam), and sometimes doesn't create enough of
* them when it is necessary.
*/
#define VISIBILITY_MAP 0
/*
* STATUS: in progress, do not use for now
* Only update if innovation is significant wrt measurement uncertainty.
*
* Large updates are causing inconsistency because of linearization errors,
* but too numerous updates are also causing inconsistency,
* so we should avoid to do not significant updates.
* An update is not significant if there are large odds that it is
* only measurement noise and that there is not much information.
*
* When the camera is not moving at all, the landmarks are converging anyway
* quite fast because of this, at very unconsistent positions of course,
* so that when the camera moves it cannot recover them.
*
* Some work needs to be done yet to prevent search ellipses from growing
* too much and integrate it better with the whole management, but this was
* for first evaluation purpose.
*
* Unfortunately it doesn't seem to improve much the situation, even if
* it is still working correctly with less computations.
* The feature is disabled for now.
*/
#define RELEVANCE_TEST 0
/*
* STATUS: in progress, do not use for now
* This uses HDseg powered Segment based slam instead of the usual point based slam.
* 0 use points
* 1 use segments
* 2 use both sgments and points
*/
#define SEGMENT_BASED 0
#if SEGMENT_BASED>1
#define SEGMENT_NOISE_FACTOR 5
#else
#define SEGMENT_NOISE_FACTOR 1
#endif
#if SEGMENT_BASED
#ifndef HAVE_MODULE_DSEG
#error "dseg module is required for segment based slam"
#endif
#endif
/** ############################################################################
* #############################################################################
* Includes
* ###########################################################################*/
#include <iostream>
#include <boost/shared_ptr.hpp>
//#include <boost/filesystem/operations.hpp>
#include <boost/filesystem.hpp>
#include <time.h>
#include <map>
#include <getopt.h>
#include "kernel/keyValueFile.hpp"
// jafar debug include
#include "kernel/jafarDebug.hpp"
#include "kernel/timingTools.hpp"
#include "kernel/dataLog.hpp"
#include "kernel/threads.hpp"
#include "jmath/random.hpp"
#include "jmath/matlab.hpp"
#include "jmath/ublasExtra.hpp"
#include "jmath/angle.hpp"
#include "rtslam/rtSlam.hpp"
#include "rtslam/rawProcessors.hpp"
#include "rtslam/rawSegProcessors.hpp"
#include "rtslam/robotOdometry.hpp"
#include "rtslam/robotConstantVelocity.hpp"
#include "rtslam/robotInertial.hpp"
#include "rtslam/sensorPinhole.hpp"
#include "rtslam/sensorAbsloc.hpp"
#include "rtslam/landmarkAnchoredHomogeneousPoint.hpp"
#include "rtslam/landmarkAnchoredHomogeneousPointsLine.hpp"
//#include "rtslam/landmarkEuclideanPoint.hpp"
#include "rtslam/observationFactory.hpp"
#include "rtslam/observationMakers.hpp"
#include "rtslam/activeSearch.hpp"
#include "rtslam/activeSegmentSearch.hpp"
#include "rtslam/featureAbstract.hpp"
#include "rtslam/rawImage.hpp"
#include "rtslam/descriptorImagePoint.hpp"
#include "rtslam/descriptorSeg.hpp"
#include "rtslam/dataManagerOnePointRansac.hpp"
#include "rtslam/sensorManager.hpp"
#include "rtslam/hardwareSensorCameraFirewire.hpp"
#include "rtslam/hardwareSensorCameraUeye.hpp"
#include "rtslam/hardwareEstimatorMti.hpp"
#include "rtslam/hardwareSensorGpsGenom.hpp"
#include "rtslam/hardwareSensorMocap.hpp"
#include "rtslam/hardwareEstimatorOdo.hpp"
#include "rtslam/display_qt.hpp"
#include "rtslam/display_gdhe.hpp"
#include "rtslam/simuRawProcessors.hpp"
#include "rtslam/hardwareSensorAdhocSimulator.hpp"
#include "rtslam/hardwareEstimatorInertialAdhocSimulator.hpp"
#include "rtslam/exporterSocket.hpp"
/** ############################################################################
* #############################################################################
* types variables functions
* ###########################################################################*/
using namespace jblas;
using namespace jafar;
using namespace jafar::jmath;
using namespace jafar::jmath::ublasExtra;
using namespace jafar::rtslam;
using namespace boost;
typedef ImagePointObservationMaker<ObservationPinHoleEuclideanPoint, SensorPinhole, LandmarkEuclideanPoint,
AppearanceImagePoint, SensorAbstract::PINHOLE, LandmarkAbstract::PNT_EUC> PinholeEucpObservationMaker;
typedef ImagePointObservationMaker<ObservationPinHoleEuclideanPoint, SensorPinhole, LandmarkEuclideanPoint,
simu::AppearanceSimu, SensorAbstract::PINHOLE, LandmarkAbstract::PNT_EUC> PinholeEucpSimuObservationMaker;
typedef ImagePointObservationMaker<ObservationPinHoleAnchoredHomogeneousPoint, SensorPinhole, LandmarkAnchoredHomogeneousPoint,
AppearanceImagePoint, SensorAbstract::PINHOLE, LandmarkAbstract::PNT_AH> PinholeAhpObservationMaker;
typedef ImagePointObservationMaker<ObservationPinHoleAnchoredHomogeneousPoint, SensorPinhole, LandmarkAnchoredHomogeneousPoint,
simu::AppearanceSimu, SensorAbstract::PINHOLE, LandmarkAbstract::PNT_AH> PinholeAhpSimuObservationMaker;
typedef DataManagerOnePointRansac<RawImage, SensorPinhole, FeatureImagePoint, image::ConvexRoi, ActiveSearchGrid, ImagePointHarrisDetector, ImagePointZnccMatcher> DataManager_ImagePoint_Ransac;
typedef DataManagerOnePointRansac<simu::RawSimu, SensorPinhole, simu::FeatureSimu, image::ConvexRoi, ActiveSearchGrid, simu::DetectorSimu<image::ConvexRoi>, simu::MatcherSimu<image::ConvexRoi> > DataManager_ImagePoint_Ransac_Simu;
#if SEGMENT_BASED
typedef SegmentObservationMaker<ObservationPinHoleAnchoredHomogeneousPointsLine, SensorPinhole, LandmarkAnchoredHomogeneousPointsLine,
AppearanceImageSegment, SensorAbstract::PINHOLE, LandmarkAbstract::LINE_AHPL> PinholeAhplObservationMaker;
typedef SegmentObservationMaker<ObservationPinHoleAnchoredHomogeneousPointsLine, SensorPinhole, LandmarkAnchoredHomogeneousPointsLine,
simu::AppearanceSimu, SensorAbstract::PINHOLE, LandmarkAbstract::LINE_AHPL> PinholeAhplSimuObservationMaker;
typedef DataManagerOnePointRansac<RawImage, SensorPinhole, FeatureImageSegment, image::ConvexRoi, ActiveSegmentSearchGrid, HDsegDetector, DsegMatcher> DataManager_ImageSeg_Test;
typedef DataManagerOnePointRansac<simu::RawSimu, SensorPinhole, simu::FeatureSimu, image::ConvexRoi, ActiveSegmentSearchGrid, simu::DetectorSimu<image::ConvexRoi>, simu::MatcherSimu<image::ConvexRoi> > DataManager_Segment_Ransac_Simu;
#endif
int mode = 0;
time_t rseed;
/** ############################################################################
* #############################################################################
* program parameters
* ###########################################################################*/
enum { iDispQt = 0, iDispGdhe, iRenderAll, iReplay, iDump, iRandSeed, iPause, iVerbose, iMap, iRobot, iCamera, iTrigger, iGps, iSimu, iExport, nIntOpts };
int intOpts[nIntOpts] = {0};
const int nFirstIntOpt = 0, nLastIntOpt = nIntOpts-1;
enum { fFreq = 0, fShutter, fHeading, nFloatOpts };
double floatOpts[nFloatOpts] = {0.0};
const int nFirstFloatOpt = nIntOpts, nLastFloatOpt = nIntOpts+nFloatOpts-1;
enum { sDataPath = 0, sConfigSetup, sConfigEstimation, sLog, nStrOpts };
std::string strOpts[nStrOpts];
const int nFirstStrOpt = nIntOpts+nFloatOpts, nLastStrOpt = nIntOpts+nFloatOpts+nStrOpts-1;
enum { bHelp = 0, bUsage, nBreakingOpts };
const int nFirstBreakingOpt = nIntOpts+nFloatOpts+nStrOpts, nLastBreakingOpt = nIntOpts+nFloatOpts+nStrOpts+nBreakingOpts-1;
/// !!WARNING!! be careful that options are in the same order above and below
#ifndef GENOM
struct option long_options[] = {
// int options
{"disp-2d", 2, 0, 0},
{"disp-3d", 2, 0, 0},
{"render-all", 2, 0, 0},
{"replay", 2, 0, 0},
{"dump", 2, 0, 0},
{"rand-seed", 2, 0, 0},
{"pause", 2, 0, 0},
{"verbose", 2, 0, 0},
{"map", 2, 0, 0},
{"robot", 2, 0, 0}, // should be in config file
{"camera", 2, 0, 0},
{"trigger", 2, 0, 0}, // should be in config file
{"gps", 2, 0, 0},
{"simu", 2, 0, 0},
{"export", 2, 0, 0},
// double options
{"freq", 2, 0, 0}, // should be in config file
{"shutter", 2, 0, 0}, // should be in config file
{"heading", 2, 0, 0},
// string options
{"data-path", 1, 0, 0},
{"config-setup", 1, 0, 0},
{"config-estimation", 1, 0, 0},
{"log", 1, 0, 0},
// breaking options
{"help",0,0,0},
{"usage",0,0,0},
};
#endif
/** ############################################################################
* #############################################################################
* Config data
* ###########################################################################*/
const int slam_priority = -20; // needs to be started as root to be < 0
const int display_priority = 10;
const int display_period = 100; // ms
const unsigned N_FRAMES = 500000;
class ConfigSetup: public kernel::KeyValueFileSaveLoad
{
public:
/// SENSOR
jblas::vec6 SENSOR_POSE_CONSTVEL; /// camera pose in constant velocity (x,y,z,roll,pitch,yaw) (m,deg)
jblas::vec6 SENSOR_POSE_INERTIAL; /// camera pose in inertial (x,y,z,roll,pitch,yaw) (m,deg)
jblas::vec6 GPS_POSE; /// GPS pose (x,y,z,roll,pitch,yaw) (m,deg)
jblas::vec6 ROBOT_POSE; /// the transformation between the slam robot (the main sensor, camera or imu) and the real robot = pose of the real robot in the slam robot frame, just like the other sensors
unsigned CAMERA_TYPE; /// camera type (0 = firewire, 1 = firewire format7, 2 = USB, 3 = UEYE)
std::string CAMERA_DEVICE; /// camera device (firewire ID or device)
unsigned IMG_WIDTH; /// image width
unsigned IMG_HEIGHT; /// image height
jblas::vec4 INTRINSIC; /// intrisic calibration parameters (u0,v0,alphaU,alphaV)
jblas::vec3 DISTORTION; /// distortion calibration parameters
/// SIMU SENSOR
unsigned IMG_WIDTH_SIMU;
unsigned IMG_HEIGHT_SIMU;
jblas::vec4 INTRINSIC_SIMU;
jblas::vec3 DISTORTION_SIMU;
/// CONSTANT VELOCITY
double UNCERT_VLIN; /// initial uncertainty stdev on linear velocity (m/s)
double UNCERT_VANG; /// initial uncertainty stdev on angular velocity (rad/s)
double PERT_VLIN; /// perturbation on linear velocity, ie non-constantness (m/s per sqrt(s))
double PERT_VANG; /// perturbation on angular velocity, ie non-constantness (rad/s per sqrt(s))
/// INERTIAL (also using UNCERT_VLIN)
std::string MTI_DEVICE; /// IMU device
double ACCELERO_FULLSCALE; /// full scale of accelerometers (m/s2) (MTI: 17)
double ACCELERO_NOISE; /// noise stdev of accelerometers (m/s2) (MTI: 0.002*sqrt(30) )
double GYRO_FULLSCALE; /// full scale of gyrometers (rad/s) (MTI: rad(300) )
double GYRO_NOISE; /// noise stdev of gyrometers (rad/s) (MTI: rad(0.05)*sqrt(40) )
double UNCERT_GRAVITY; /// initial gravity uncertainty (% of 9.81)
double UNCERT_ABIAS; /// initial accelerometer bias uncertainty (% of ACCELERO_FULLSCALE)
double UNCERT_WBIAS; /// initial gyrometer bias uncertainty (% of GYRO_FULLSCALE)
double PERT_AERR; /// noise stdev coeff of accelerometers, for testing purpose (% of ACCELERO_NOISE)
double PERT_WERR; /// noise stdev coeff of gyrometers, for testing purpose (% of GYRO_NOISE)
double PERT_RANWALKACC; /// IMU a_bias random walk (m/s2 per sqrt(s))
double PERT_RANWALKGYRO; /// IMU w_bias random walk (rad/s per sqrt(s))
double UNCERT_HEADING; /// initial heading uncertainty
double UNCERT_ATTITUDE; /// initial attitude angles uncertainty
double IMU_TIMESTAMP_CORRECTION; /// correction to add to the IMU timestamp for synchronization (s)
double GPS_TIMESTAMP_CORRECTION; /// correction to add to the GPS timestamp for synchronization (s)
/// Odometry noise variance to distance ratios
double dxNDR; /// Odometry noise in position increment (m per sqrt(m))
double dvNDR; /// Odometry noise in orientation increment (rad per sqrt(m))
double POS_TIMESTAMP_CORRECTION; /// correction to add to the POS timestamp for synchronization (s)
/// SIMU INERTIAL
double SIMU_IMU_TIMESTAMP_CORRECTION;
double SIMU_IMU_FREQ;
double SIMU_IMU_GRAVITY;
double SIMU_IMU_GYR_BIAS;
double SIMU_IMU_GYR_BIAS_NOISESTD;
double SIMU_IMU_GYR_GAIN;
double SIMU_IMU_GYR_GAIN_NOISESTD;
double SIMU_IMU_RANDWALKGYR_FACTOR;
double SIMU_IMU_ACC_BIAS;
double SIMU_IMU_ACC_BIAS_NOISESTD;
double SIMU_IMU_ACC_GAIN;
double SIMU_IMU_ACC_GAIN_NOISESTD;
double SIMU_IMU_RANDWALKACC_FACTOR;
public:
virtual void loadKeyValueFile(jafar::kernel::KeyValueFile const& keyValueFile);
virtual void saveKeyValueFile(jafar::kernel::KeyValueFile& keyValueFile);
} configSetup;
class ConfigEstimation: public kernel::KeyValueFileSaveLoad
{
public:
/// MISC
unsigned CORRECTION_SIZE; /// number of coefficients for the distortion correction polynomial
/// FILTER
unsigned MAP_SIZE; /// map size in # of states, robot + landmarks
double PIX_NOISE; /// measurement noise of a point
double PIX_NOISE_SIMUFACTOR;
/// LANDMARKS
double D_MIN; /// inverse depth mean initialization
double REPARAM_TH; /// reparametrization threshold
unsigned GRID_HCELLS;
unsigned GRID_VCELLS;
unsigned GRID_MARGIN;
unsigned GRID_SEPAR;
double RELEVANCE_TH; /// (# of sigmas)
double MAHALANOBIS_TH; /// (# of sigmas)
unsigned N_UPDATES_TOTAL; /// max number of landmarks to update every frame
unsigned N_UPDATES_RANSAC; /// max number of landmarks to update with ransac every frame
unsigned N_INIT; /// maximum number of landmarks to try to initialize every frame
unsigned N_RECOMP_GAINS; /// how many times information gain is recomputed to resort observations in active search
double RANSAC_LOW_INNOV; /// ransac low innovation threshold (pixels)
unsigned RANSAC_NTRIES; /// number of base observation used to initialize a ransac set
/// RAW PROCESSING
unsigned HARRIS_CONV_SIZE;
double HARRIS_TH;
double HARRIS_EDDGE;
unsigned DESC_SIZE; /// descriptor patch size (odd value)
bool MULTIVIEW_DESCRIPTOR; /// whether use or not the multiview descriptor
double DESC_SCALE_STEP; /// MultiviewDescriptor: min change of scale (ratio)
double DESC_ANGLE_STEP; /// MultiviewDescriptor: min change of point of view (deg)
int DESC_PREDICTION_TYPE; /// type of prediction from descriptor (0 = none, 1 = affine, 2 = homographic)
unsigned PATCH_SIZE; /// patch size used for matching
unsigned MAX_SEARCH_SIZE; /// if the search area is larger than this # of pixels, we bound it
unsigned KILL_SEARCH_SIZE; /// if the search area is larger than this # of pixels, we vote for killing the landmark
double MATCH_TH; /// ZNCC score threshold
double MIN_SCORE; /// min ZNCC score under which we don't finish to compute the value of the score
double PARTIAL_POSITION; /// position in the patch where we test if we finish the correlation computation
public:
virtual void loadKeyValueFile(jafar::kernel::KeyValueFile const& keyValueFile);
virtual void saveKeyValueFile(jafar::kernel::KeyValueFile& keyValueFile);
} configEstimation;
/** ############################################################################
* #############################################################################
* Slam function
* ###########################################################################*/
world_ptr_t worldPtr;
boost::scoped_ptr<kernel::DataLogger> dataLogger;
sensor_manager_ptr_t sensorManager;
boost::shared_ptr<ExporterAbstract> exporter;
#ifdef HAVE_MODULE_QDISPLAY
display::ViewerQt *viewerQt = NULL;
#endif
#ifdef HAVE_MODULE_GDHE
display::ViewerGdhe *viewerGdhe = NULL;
#endif
kernel::VariableCondition<int> rawdata_condition(0);
void demo_slam_init()
{ try {
// preprocess options
if (intOpts[iReplay] & 1) mode = 2; else
if (intOpts[iDump]) mode = 1; else
mode = 0;
if (strOpts[sConfigSetup] == "#!@")
{
if (intOpts[iReplay] & 1)
strOpts[sConfigSetup] = strOpts[sDataPath] + "/setup.cfg";
else
strOpts[sConfigSetup] = "data/setup.cfg";
}
if (intOpts[iReplay] & 1) intOpts[iExport] = 0;
if (strOpts[sConfigSetup][0] == '@' && strOpts[sConfigSetup][1] == '/')
strOpts[sConfigSetup] = strOpts[sDataPath] + strOpts[sConfigSetup].substr(1);
if (strOpts[sConfigEstimation][0] == '@' && strOpts[sConfigEstimation][1] == '/')
strOpts[sConfigEstimation] = strOpts[sDataPath] + strOpts[sConfigEstimation].substr(1);
if (!(intOpts[iReplay] & 1) && intOpts[iDump])
{
boost::filesystem::remove(strOpts[sDataPath] + "/setup.cfg");
boost::filesystem::remove(strOpts[sDataPath] + "/setup.cfg.maybe");
if (intOpts[iReplay] == 2)
boost::filesystem::copy_file(strOpts[sConfigSetup], strOpts[sDataPath] + "/setup.cfg.maybe"/*, boost::filesystem::copy_option::overwrite_if_exists*/);
else
boost::filesystem::copy_file(strOpts[sConfigSetup], strOpts[sDataPath] + "/setup.cfg"/*, boost::filesystem::copy_option::overwrite_if_exists*/);
}
#ifndef HAVE_MODULE_QDISPLAY
intOpts[iDispQt] = 0;
#endif
#ifndef HAVE_MODULE_GDHE
intOpts[iDispGdhe] = 0;
#endif
if (strOpts[sLog].size() == 1)
{
if (strOpts[sLog][0] == '0') strOpts[sLog] = ""; else
if (strOpts[sLog][0] == '1') strOpts[sLog] = "rtslam.log";
}
// init
worldPtr.reset(new WorldAbstract());
std::cout << "Loading config files " << strOpts[sConfigSetup] << " and " << strOpts[sConfigEstimation] << std::endl;
configSetup.load(strOpts[sConfigSetup]);
configEstimation.load(strOpts[sConfigEstimation]);
// deal with the random seed
rseed = jmath::get_srand();
if (intOpts[iRandSeed] != 0 && intOpts[iRandSeed] != 1)
rseed = intOpts[iRandSeed];
if (!(intOpts[iReplay] & 1) && intOpts[iDump]) {
std::fstream f((strOpts[sDataPath] + std::string("/rseed.log")).c_str(), std::ios_base::out);
f << rseed << std::endl;
f.close();
}
else if ((intOpts[iReplay] & 1) && intOpts[iRandSeed] == 1) {
std::fstream f((strOpts[sDataPath] + std::string("/rseed.log")).c_str(), std::ios_base::in);
f >> rseed;
f.close();
}
intOpts[iRandSeed] = rseed;
std::cout << "Random seed " << rseed << std::endl;
rtslam::srand(rseed);
#ifdef HAVE_MODULE_QDISPLAY
if (intOpts[iDispQt])
{
display::ViewerQt *viewerQt = new display::ViewerQt(8, configEstimation.MAHALANOBIS_TH, false, "data/rendered2D_%02d-%06d.png");
worldPtr->addDisplayViewer(viewerQt, display::ViewerQt::id());
}
#endif
#ifdef HAVE_MODULE_GDHE
if (intOpts[iDispGdhe])
{
#if ATRV
display::ViewerGdhe *viewerGdhe = new display::ViewerGdhe("atrv", configEstimation.MAHALANOBIS_TH, "localhost");
#else
display::ViewerGdhe *viewerGdhe = new display::ViewerGdhe("camera", configEstimation.MAHALANOBIS_TH, "localhost");
#endif
boost::filesystem::path ram_path("/mnt/ram");
if (boost::filesystem::exists(ram_path) && boost::filesystem::is_directory(ram_path))
viewerGdhe->setConvertTempPath("/mnt/ram");
worldPtr->addDisplayViewer(viewerGdhe, display::ViewerGdhe::id());
}
#endif
vec intrinsic, distortion;
int img_width, img_height;
if (intOpts[iSimu] != 0)
{
img_width = configSetup.IMG_WIDTH_SIMU;
img_height = configSetup.IMG_HEIGHT_SIMU;
intrinsic = configSetup.INTRINSIC_SIMU;
distortion = configSetup.DISTORTION_SIMU;
} else
{
img_width = configSetup.IMG_WIDTH;
img_height = configSetup.IMG_HEIGHT;
intrinsic = configSetup.INTRINSIC;
distortion = configSetup.DISTORTION;
}
if (!strOpts[sLog].empty())
{
dataLogger.reset(new kernel::DataLogger(strOpts[sDataPath] + "/" + strOpts[sLog]));
dataLogger->writeCurrentDate();
dataLogger->writeNewLine();
#ifndef GENOM
// FIXME do it for genom
// write options to log
std::ostringstream oss;
for(int i = 0; i < nIntOpts; ++i)
{ oss << long_options[i+nFirstIntOpt].name << " = " << intOpts[i]; dataLogger->writeComment(oss.str()); oss.str(""); }
for(int i = 0; i < nFloatOpts; ++i)
{ oss << long_options[i+nFirstFloatOpt].name << " = " << floatOpts[i]; dataLogger->writeComment(oss.str()); oss.str(""); }
for(int i = 0; i < nStrOpts; ++i)
{ oss << long_options[i+nFirstStrOpt].name << " = " << strOpts[i]; dataLogger->writeComment(oss.str()); oss.str(""); }
dataLogger->writeNewLine();
#endif
}
switch (intOpts[iVerbose])
{
case 0: debug::DebugStream::setLevel("rtslam", debug::DebugStream::Off); break;
case 1: debug::DebugStream::setLevel("rtslam", debug::DebugStream::Trace); break;
case 2: debug::DebugStream::setLevel("rtslam", debug::DebugStream::Warning); break;
case 3: debug::DebugStream::setLevel("rtslam", debug::DebugStream::Debug); break;
case 4: debug::DebugStream::setLevel("rtslam", debug::DebugStream::VerboseDebug); break;
default: debug::DebugStream::setLevel("rtslam", debug::DebugStream::VeryVerboseDebug); break;
}
// pin-hole parameters in BOOST format
boost::shared_ptr<ObservationFactory> obsFact(new ObservationFactory());
#if SEGMENT_BASED
if (intOpts[iSimu] != 0)
{
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeAhplSimuObservationMaker(
configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE, 30, 0.5, 0.5, configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
} else
{
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeAhplObservationMaker(
configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE, 30, 0.5, 0.5, configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
}
#endif
#if SEGMENT_BASED != 1
if (intOpts[iSimu] != 0)
{
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeEucpSimuObservationMaker(
configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeAhpSimuObservationMaker(
configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
} else
{
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeEucpObservationMaker(
configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
obsFact->addMaker(boost::shared_ptr<ObservationMakerAbstract>(new PinholeAhpObservationMaker(
configEstimation.D_MIN, configEstimation.PATCH_SIZE)));
}
#endif
// ---------------------------------------------------------------------------
// --- INIT ------------------------------------------------------------------
// ---------------------------------------------------------------------------
// INIT : 1 map and map-manager, 2 robs, 3 sens and data-manager.
// 1. Create maps.
map_ptr_t mapPtr(new MapAbstract(configEstimation.MAP_SIZE));
mapPtr->linkToParentWorld(worldPtr);
// 1b. Create map manager.
landmark_factory_ptr_t pointLmkFactory;
landmark_factory_ptr_t segLmkFactory;
#if SEGMENT_BASED
segLmkFactory.reset(new LandmarkFactory<LandmarkAnchoredHomogeneousPointsLine, LandmarkAnchoredHomogeneousPointsLine>());
#endif
#if SEGMENT_BASED != 1
pointLmkFactory.reset(new LandmarkFactory<LandmarkAnchoredHomogeneousPoint, LandmarkEuclideanPoint>());
#endif
map_manager_ptr_t mmPoint;
map_manager_ptr_t mmSeg;
switch(intOpts[iMap])
{
case 0: { // odometry
if(pointLmkFactory != NULL)
mmPoint.reset(new MapManagerOdometry(pointLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE));
if(segLmkFactory != NULL)
mmSeg.reset(new MapManagerOdometry(segLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE));
break;
}
case 1: { // global
if(pointLmkFactory != NULL)
mmPoint.reset(new MapManagerGlobal(pointLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE, 30, 0.5, 0.5));
if(segLmkFactory != NULL)
mmSeg.reset(new MapManagerGlobal(segLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE, 30, 0.5, 0.5));
break;
}
case 2: { // local/multimap
if(pointLmkFactory != NULL)
mmPoint.reset(new MapManagerLocal(pointLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE));
if(segLmkFactory != NULL)
mmSeg.reset(new MapManagerLocal(segLmkFactory, configEstimation.REPARAM_TH, configEstimation.KILL_SEARCH_SIZE));
break;
}
}
if(mmPoint != NULL)
mmPoint->linkToParentMap(mapPtr);
if(mmSeg != NULL)
mmSeg->linkToParentMap(mapPtr);
// simulation environment
boost::shared_ptr<simu::AdhocSimulator> simulator;
if (intOpts[iSimu] != 0)
{
simulator.reset(new simu::AdhocSimulator());
#if SEGMENT_BASED
jblas::vec11 pose;
#else
jblas::vec3 pose;
#endif
const int maxnpoints = 1000;
int npoints = 0;
#if SEGMENT_BASED
double points[maxnpoints][11];
#else
double points[maxnpoints][3];
#endif
switch (intOpts[iSimu]/10)
{
#if SEGMENT_BASED
case 1: {
// 3D cube
const int npoints_ = 36; npoints = npoints_;
double tmp[npoints_][11] = {
{0,0,0,5,-1,-1,1,5,-1, 1,1}, {0,0,0,5,1,1,1,5,1,-1,1}, {0,0,0,5,-1,1,1,5, 1,1,1}, {0,0,0,5,-1,-1,1,5,1,-1,1},
{0,0,0,3,-1,-1,1,3,-1, 1,1}, {0,0,0,3,1,1,1,3,1,-1,1}, {0,0,0,3,-1,1,1,3, 1,1,1}, {0,0,0,3,-1,-1,1,3,1,-1,1},
{0,0,0,5,-1,-1,1,3,-1,-1,1}, {0,0,0,5,1,1,1,3,1, 1,1}, {0,0,0,5,-1,1,1,3,-1,1,1}, {0,0,0,5, 1,-1,1,3,1,-1,1},
{0,0,0,5,-4,-1,1,5,-4, 1,1}, {0,0,0,5,-2,1,1,5,-2,-1,1}, {0,0,0,5,-4,1,1,5,-2,1,1}, {0,0,0,5,-4,-1,1,5,-2,-1,1},
{0,0,0,3,-4,-1,1,3,-4, 1,1}, {0,0,0,3,-2,1,1,3,-2,-1,1}, {0,0,0,3,-4,1,1,3,-2,1,1}, {0,0,0,3,-4,-1,1,3,-2,-1,1},
{0,0,0,5,-4,-1,1,3,-4,-1,1}, {0,0,0,5,-2,1,1,3,-2, 1,1}, {0,0,0,5,-4,1,1,3,-4,1,1}, {0,0,0,5,-2,-1,1,3,-2,-1,1},
{0,0,0,5, 2,-1,1,5, 2, 1,1}, {0,0,0,5,4,1,1,5,4,-1,1}, {0,0,0,5,2,1,1,5, 4,1,1}, {0,0,0,5, 2,-1,1,5,4,-1,1},
{0,0,0,3, 2,-1,1,3, 2, 1,1}, {0,0,0,3,4,1,1,3,4,-1,1}, {0,0,0,3,2,1,1,3, 4,1,1}, {0,0,0,3, 2,-1,1,3,4,-1,1},
{0,0,0,5, 2,-1,1,3, 2,-1,1}, {0,0,0,5,4,1,1,3,4, 1,1}, {0,0,0,5,2,1,1,3, 2,1,1}, {0,0,0,5, 4,-1,1,3,4,-1,1}
};
memcpy(points, tmp, npoints*11*sizeof(double));
break;
}
case 2: {
// 2D square
const int npoints_ = 4; npoints = npoints_;
double tmp[npoints_][11] = {
{0,0,0,5,-1,-1,1,5,-1,1,1}, {0,0,0,5,1,1,1,5,1,-1,1}, {0,0,0,5,-1,1,1,5,1,1,1}, {0,0,0,5,-1,-1,1,5,1,-1,1}
};
memcpy(points, tmp, npoints*11*sizeof(double));
break;
}
case 3: {
// almost 2D square
const int npoints_ = 4; npoints = npoints_;
double tmp[npoints_][11] = {
{0,0,0,4,-1,-1,1,4,-1,1,1}, {0,0,0,4,1,1,1,4,1,-1,1}, {0,0,0,5,-1,1,1,5,1,1,1}, {0,0,0,5,-1,-1,1,5,1,-1,1}
};
memcpy(points, tmp, npoints*11*sizeof(double));
break;
}
default: npoints = 0;
#else
case 1: {
// 3D regular grid
const int npoints_ = 3*11*13; npoints = npoints_;
for(int i = 0, z = -1; z <= 1; ++z) for(int y = -3; y <= 7; ++y) for(int x = -6; x <= 6; ++x, ++i)
{ points[i][0] = x*1.0; points[i][1] = y*1.0; points[i][2] = z*1.0; }
break;
}
case 2: {
// 2D square
const int npoints_ = 5; npoints = npoints_;
double tmp[npoints_][3] = { {5,-1,-1}, {5,-1,1}, {5,1,1}, {5,1,-1}, {5,0,0} };
memcpy(points, tmp, npoints*3*sizeof(double));
break;
}
case 3: {
// almost 2D square
const int npoints_ = 5; npoints = npoints_;
double tmp[npoints_][3] = { {5,-1,-1}, {5,-1,1}, {5,1,1}, {5,1,-1}, {4,0,0} };
memcpy(points, tmp, npoints*3*sizeof(double));
break;
}
case 4: {
// far 3D regular grid
const int npoints_ = 3*11*13; npoints = npoints_;
for(int i = 0, z = -1; z <= 1; ++z) for(int y = -3; y <= 7; ++y) for(int x = -6; x <= 6; ++x, ++i)
{ points[i][0] = x*1.0+100; points[i][1] = y*10.0; points[i][2] = z*10.0; }
break;
}
default: npoints = 0;
#endif
}
// add landmarks
for(int i = 0; i < npoints; ++i)
{
pose(0) = points[i][0]; pose(1) = points[i][1]; pose(2) = points[i][2];
#if !SEGMENT_BASED
simu::Landmark *lmk = new simu::Landmark(LandmarkAbstract::POINT, pose);
#else
pose(3) = points[i][3]; pose(4) = points[i][4]; pose(5) = points[i][5];
pose(6) = points[i][6]; pose(7) = points[i][7]; pose(8) = points[i][8];
pose(9) = points[i][9]; pose(10) = points[i][10];
simu::Landmark *lmk = new simu::Landmark(LandmarkAbstract::LINE, pose);
#endif
simulator->addLandmark(lmk);
}
}
// 2. Create robots.
robot_ptr_t robPtr1;
if (intOpts[iRobot] == 0) // constant velocity
{
robconstvel_ptr_t robPtr1_(new RobotConstantVelocity(mapPtr));
robPtr1_->setVelocityStd(configSetup.UNCERT_VLIN, configSetup.UNCERT_VANG);
robPtr1_->setId();
double _v[6] = {
configSetup.PERT_VLIN, configSetup.PERT_VLIN, configSetup.PERT_VLIN,
configSetup.PERT_VANG, configSetup.PERT_VANG, configSetup.PERT_VANG };
vec pertStd = createVector<6>(_v);
robPtr1_->perturbation.set_std_continuous(pertStd);
robPtr1_->constantPerturbation = false;
robPtr1 = robPtr1_;
if (intOpts[iTrigger] != 0)
{
// just to initialize the MTI as an external trigger controlling shutter time
hardware::HardwareEstimatorMti hardEst1(
configSetup.MTI_DEVICE, intOpts[iTrigger], floatOpts[fFreq], floatOpts[fShutter], 1, mode, strOpts[sDataPath]);
floatOpts[fFreq] = hardEst1.getFreq();
}
}
else
if (intOpts[iRobot] == 1) // inertial
{
robinertial_ptr_t robPtr1_(new RobotInertial(mapPtr));
robPtr1_->setInitialStd(
configSetup.UNCERT_VLIN,
configSetup.UNCERT_ABIAS*configSetup.ACCELERO_FULLSCALE,
configSetup.UNCERT_WBIAS*configSetup.GYRO_FULLSCALE,
configSetup.UNCERT_GRAVITY*9.81);
robPtr1_->setId();
double aerr = configSetup.PERT_AERR * configSetup.ACCELERO_NOISE;
double werr = configSetup.PERT_WERR * configSetup.GYRO_NOISE;
double _v[12] = {
aerr, aerr, aerr, werr, werr, werr,
configSetup.PERT_RANWALKACC, configSetup.PERT_RANWALKACC, configSetup.PERT_RANWALKACC,
configSetup.PERT_RANWALKGYRO, configSetup.PERT_RANWALKGYRO, configSetup.PERT_RANWALKGYRO};
vec pertStd = createVector<12>(_v);
robPtr1_->perturbation.set_std_continuous(pertStd);
robPtr1_->constantPerturbation = false;
hardware::hardware_estimator_ptr_t hardEst1;
if (intOpts[iSimu] != 0)
{
boost::shared_ptr<hardware::HardwareEstimatorInertialAdhocSimulator> hardEst1_(
new hardware::HardwareEstimatorInertialAdhocSimulator(configSetup.SIMU_IMU_FREQ, 50, simulator, robPtr1_->id()));
hardEst1_->setSyncConfig(configSetup.SIMU_IMU_TIMESTAMP_CORRECTION);
hardEst1_->setErrors(configSetup.SIMU_IMU_GRAVITY,
configSetup.SIMU_IMU_GYR_BIAS, configSetup.SIMU_IMU_GYR_BIAS_NOISESTD,
configSetup.SIMU_IMU_GYR_GAIN, configSetup.SIMU_IMU_GYR_GAIN_NOISESTD,
configSetup.SIMU_IMU_RANDWALKGYR_FACTOR * configSetup.PERT_RANWALKGYRO,
configSetup.SIMU_IMU_ACC_BIAS, configSetup.SIMU_IMU_ACC_BIAS_NOISESTD,
configSetup.SIMU_IMU_ACC_GAIN, configSetup.SIMU_IMU_ACC_GAIN_NOISESTD,
configSetup.SIMU_IMU_RANDWALKACC_FACTOR * configSetup.PERT_RANWALKACC);
hardEst1 = hardEst1_;
} else
{
boost::shared_ptr<hardware::HardwareEstimatorMti> hardEst1_(new hardware::HardwareEstimatorMti(
configSetup.MTI_DEVICE, intOpts[iTrigger], floatOpts[fFreq], floatOpts[fShutter], 1024, mode, strOpts[sDataPath]));
if (intOpts[iTrigger] != 0) floatOpts[fFreq] = hardEst1_->getFreq();
hardEst1_->setSyncConfig(configSetup.IMU_TIMESTAMP_CORRECTION);
//hardEst1_->setUseForInit(true);
//hardEst1_->setNeedInit(true);
//hardEst1_->start();
hardEst1 = hardEst1_;
}
robPtr1_->setHardwareEstimator(hardEst1);
robPtr1 = robPtr1_;
} else
if (intOpts[iRobot] == 2) // odometry
{
robodo_ptr_t robPtr1_(new RobotOdometry(mapPtr));
robPtr1_->setId();
std::cout<<"configSetup.dxNDR "<<configSetup.dxNDR<<std::endl;
std::cout<<"configSetup.dvNDR "<<configSetup.dvNDR<<std::endl;
double _v[6] = {configSetup.dxNDR, configSetup.dxNDR, configSetup.dxNDR,
configSetup.dvNDR, configSetup.dvNDR, configSetup.dvNDR};
vec pertStd = createVector<6>(_v);
robPtr1_->perturbation.set_std_continuous(pertStd);
robPtr1_->constantPerturbation = false;
hardware::hardware_estimator_ptr_t hardEst2;
boost::shared_ptr<hardware::HardwareEstimatorOdo> hardEst2_(new hardware::HardwareEstimatorOdo(
intOpts[iTrigger], floatOpts[fFreq], floatOpts[fShutter], 1024, mode, strOpts[sDataPath]));
if (intOpts[iTrigger] != 0) floatOpts[fFreq] = hardEst2_->getFreq();
hardEst2_->setSyncConfig(configSetup.POS_TIMESTAMP_CORRECTION);
hardEst2 = hardEst2_;
robPtr1_->setHardwareEstimator(hardEst2);
robPtr1 = robPtr1_;
}
robPtr1->linkToParentMap(mapPtr);
robPtr1->pose.x(quaternion::originFrame());
robPtr1->setPoseStd(0,0,0, 0,0,floatOpts[fHeading],
0,0,0, configSetup.UNCERT_ATTITUDE,configSetup.UNCERT_ATTITUDE,configSetup.UNCERT_HEADING);
robPtr1->robot_pose = configSetup.ROBOT_POSE;
if (dataLogger) dataLogger->addLoggable(*robPtr1.get());
if (intOpts[iSimu] != 0)
{
simu::Robot *rob = new simu::Robot(robPtr1->id(), 6);
if (dataLogger) dataLogger->addLoggable(*rob);
switch (intOpts[iSimu]%10)
{
// horiz loop, no rotation
case 1: {
double VEL = 0.5;
rob->addWaypoint(0,0,0, 0,0,0, 0,0,0, 0,0,0);
rob->addWaypoint(1,0,0, 0,0,0, VEL,0,0, 0,0,0);
rob->addWaypoint(3,2,0, 0,0,0, 0,VEL,0, 0,0,0);
rob->addWaypoint(1,4,0, 0,0,0, -VEL,0,0, 0,0,0);
rob->addWaypoint(-1,4,0, 0,0,0, -VEL,0,0, 0,0,0);
rob->addWaypoint(-3,2,0, 0,0,0, 0,-VEL,0, 0,0,0);
rob->addWaypoint(-1,0,0, 0,0,0, VEL,0,0, 0,0,0);
rob->addWaypoint(0,0,0, 0,0,0, 0,0,0, 0,0,0);
break;
}
// two coplanar circles
case 2: {
double VEL = 0.5;
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
rob->addWaypoint(0 ,0 ,+1, 0,0,0, 0,-VEL,0 , 0,0,0);
rob->addWaypoint(0 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(0 ,0 ,-1, 0,0,0, 0,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
rob->addWaypoint(0 ,0 ,+1, 0,0,0, 0,-VEL,0 , 0,0,0);
rob->addWaypoint(0 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(0 ,0 ,-1, 0,0,0, 0,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
break;
}
// two non-coplanar circles at constant velocity
case 3: {
double VEL = 0.5;
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
rob->addWaypoint(0.25,0 ,+1, 0,0,0, VEL/4,-VEL,0 , 0,0,0);
rob->addWaypoint(0.5 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(0.25,0 ,-1, 0,0,0, -VEL/4,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
rob->addWaypoint(-0.25,0 ,+1, 0,0,0, -VEL/4,-VEL,0 , 0,0,0);
rob->addWaypoint(-0.5 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(-0.25,0 ,-1, 0,0,0, VEL/4,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
break;
}
// two non-coplanar circles with start and stop from/to null speed
case 4: {
double VEL = 0.5;
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,0, 0,0,0);
rob->addWaypoint(0 ,+1,0.1 , 0,0,0, 0,0 ,+VEL/2, 0,0,0);
rob->addWaypoint(0 ,+1,0.5 , 0,0,0, 0,0 ,+VEL/2, 0,0,0);
rob->addWaypoint(0.25,0 ,+1, 0,0,0, VEL/4,-VEL,0 , 0,0,0);
rob->addWaypoint(0.5 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(0.25,0 ,-1, 0,0,0, -VEL/4,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,+VEL, 0,0,0);
rob->addWaypoint(-0.25,0 ,+1, 0,0,0, -VEL/4,-VEL,0 , 0,0,0);
rob->addWaypoint(-0.5 ,-1,0 , 0,0,0, 0,0 ,-VEL, 0,0,0);
rob->addWaypoint(-0.25,0 ,-1, 0,0,0, VEL/4,+VEL,0 , 0,0,0);
rob->addWaypoint(0 ,+1,-0.5 , 0,0,0, 0,0 ,+VEL/2, 0,0,0);
rob->addWaypoint(0 ,+1,-0.1 , 0,0,0, 0,0 ,+VEL/2, 0,0,0);
rob->addWaypoint(0 ,+1,0 , 0,0,0, 0,0 ,0, 0,0,0);
break;
}
// horiz loop with rotation (always goes forward)
case 5: {
double VEL = 0.5;
rob->addWaypoint(0,0,0, 0,0,0, VEL/5,0,0, 0,0,0);
rob->addWaypoint(1,0,0, 0,0,0, VEL,0,0, 0,0,0);
rob->addWaypoint(3,2,0, 1*M_PI/2,0,0, 0,VEL,0, 100,0,0);
rob->addWaypoint(1,4,0, 2*M_PI/2,0,0, -VEL,0,0, 0,0,0);
rob->addWaypoint(-1,4,0, 2*M_PI/2,0,0, -VEL,0,0, 0,0,0);
rob->addWaypoint(-3,2,0, 3*M_PI/2,0,0, 0,-VEL,0, 100,0,0);
rob->addWaypoint(-1,0,0, 4*M_PI/2,0,0, VEL,0,0, 0,0,0);
rob->addWaypoint(0,0,0, 4*M_PI/2,0,0, 0,0,0, 0,0,0);
break;
}
// straight line
case 6: {
double VEL = 0.5;
rob->addWaypoint(0,0,0, 0,0,0, 0,0,0, 0,0,0);
rob->addWaypoint(1,0,0, 0,0,0, VEL,0,0, 0,0,0);
rob->addWaypoint(20,0,0, 0,0,0, VEL,0,0, 0,0,0);
break;
}
}
simulator->addRobot(rob);
}
// 3. Create sensors.
if (intOpts[iCamera])
{
pinhole_ptr_t senPtr11(new SensorPinhole(robPtr1, MapObject::UNFILTERED));
senPtr11->setId();
senPtr11->linkToParentRobot(robPtr1);
if (intOpts[iRobot] == 1)
{
senPtr11->setPose(configSetup.SENSOR_POSE_INERTIAL[0], configSetup.SENSOR_POSE_INERTIAL[1], configSetup.SENSOR_POSE_INERTIAL[2],
configSetup.SENSOR_POSE_INERTIAL[3], configSetup.SENSOR_POSE_INERTIAL[4], configSetup.SENSOR_POSE_INERTIAL[5]); // x,y,z,roll,pitch,yaw
} else
{
senPtr11->setPose(configSetup.SENSOR_POSE_CONSTVEL[0], configSetup.SENSOR_POSE_CONSTVEL[1], configSetup.SENSOR_POSE_CONSTVEL[2],
configSetup.SENSOR_POSE_CONSTVEL[3], configSetup.SENSOR_POSE_CONSTVEL[4], configSetup.SENSOR_POSE_CONSTVEL[5]); // x,y,z,roll,pitch,yaw
}
//senPtr11->pose.x(quaternion::originFrame());
senPtr11->params.setImgSize(img_width, img_height);
senPtr11->params.setIntrinsicCalibration(intrinsic, distortion, configEstimation.CORRECTION_SIZE);
//JFR_DEBUG("Correction params: " << senPtr11->params.correction);
senPtr11->params.setMiscellaneous(configEstimation.PIX_NOISE, configEstimation.D_MIN);
if (intOpts[iSimu] != 0)
{
jblas::vec6 pose;
subrange(pose, 0, 3) = subrange(senPtr11->pose.x(), 0, 3);
subrange(pose, 3, 6) = quaternion::q2e(subrange(senPtr11->pose.x(), 3, 7));
std::swap(pose(3), pose(5)); // FIXME-EULER-CONVENTION
simu::Sensor *sen = new simu::Sensor(senPtr11->id(), pose, senPtr11);
simulator->addSensor(robPtr1->id(), sen);
simulator->addObservationModel(robPtr1->id(), senPtr11->id(), LandmarkAbstract::POINT, new ObservationModelPinHoleEuclideanPoint(senPtr11));
#if SEGMENT_BASED
simulator->addObservationModel(robPtr1->id(), senPtr11->id(), LandmarkAbstract::LINE, new ObservationModelPinHoleAnchoredHomogeneousPointsLine(senPtr11));
#endif
}
// 3b. Create data manager.
boost::shared_ptr<ActiveSearchGrid> asGrid(new ActiveSearchGrid(img_width, img_height, configEstimation.GRID_HCELLS, configEstimation.GRID_VCELLS, configEstimation.GRID_MARGIN, configEstimation.GRID_SEPAR));
boost::shared_ptr<ActiveSegmentSearchGrid> assGrid(new ActiveSegmentSearchGrid(img_width, img_height, configEstimation.GRID_HCELLS, configEstimation.GRID_VCELLS, configEstimation.GRID_MARGIN, configEstimation.GRID_SEPAR));