/
testing_voxellist.cu
1160 lines (903 loc) · 46.1 KB
/
testing_voxellist.cu
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
// this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
// -- BEGIN LICENSE BLOCK ----------------------------------------------
// This file is part of the GPU Voxels Software Library.
//
// This program is free software licensed under the CDDL
// (COMMON DEVELOPMENT AND DISTRIBUTION LICENSE Version 1.0).
// You can find a copy of this license in LICENSE.txt in the top
// directory of the source code.
//
// © Copyright 2014 FZI Forschungszentrum Informatik, Karlsruhe, Germany
//
// -- END LICENSE BLOCK ------------------------------------------------
//----------------------------------------------------------------------
/*!\file
*
* \author Andreas Hermann <hermann@fzi.de>
* \date 2015-09-22
*
*/
//----------------------------------------------------------------------
#include <sstream>
#include <gpu_voxels/voxellist/BitVoxelList.h>
#include <gpu_voxels/voxellist/CountingVoxelList.h>
#include <gpu_voxels/voxelmap/ProbVoxelMap.h>
#include <gpu_voxels/voxelmap/VoxelMap.h>
#include <gpu_voxels/helpers/cuda_datatypes.h>
#include <gpu_voxels/helpers/MetaPointCloud.h>
#include <gpu_voxels/helpers/GeometryGeneration.h>
#include <gpu_voxels/test/testing_fixtures.hpp>
#include <boost/make_shared.hpp>
#include <boost/test/unit_test.hpp>
using namespace gpu_voxels;
using namespace voxellist;
using namespace voxelmap;
using namespace geometry_generation;
BOOST_FIXTURE_TEST_SUITE(voxellists, ArgsFixture)
BOOST_AUTO_TEST_CASE(collide_bitvoxellist_with_countingpermeaning_bitvoxellist)
{
PERF_MON_START("collide_bitvoxellist_with_countingpermeaning_bitvoxellist");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.0f;
BitVectorVoxelList* obstacle = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
BitVectorVoxelList* sweptVolume = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
Vector3f b_min(8.0, 8.0, 8.0);
Vector3f b_max(11.0, 11.0, 11.0);
//create the obstacle and load it in a map
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b_min, b_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
obstacle->insertMetaPointCloud(boxes, eBVM_OCCUPIED);
//generate the swept volume
std::vector<std::vector<Vector3f> > sweptVolumeCloud;
std::vector<BitVoxelMeaning> sweptVolumeMeanings;
const float swept_ratio_delta = 0.02;
const int num_swept_volumes = 50;
const int min = 0;
const int max = 30;
for (int i = 0; i < num_swept_volumes; i++)
{
Vector3f position((max-min) * swept_ratio_delta * i + min, (max-min) * swept_ratio_delta * i + min, (max-min) * swept_ratio_delta * i + min);
Vector3f positionM(position.x + 2.5f, position.y + 2.5f, position.z + 2.5f);
sweptVolumeMeanings.push_back(BitVoxelMeaning(eBVM_SWEPT_VOLUME_START + i));
sweptVolumeCloud.push_back(createBoxOfPoints(position, positionM, delta));
}
MetaPointCloud sweptVolumeMeta(sweptVolumeCloud);
sweptVolumeMeta.syncToDevice();
sweptVolume->insertMetaPointCloud(sweptVolumeMeta, sweptVolumeMeanings);
//collide the two lists
std::vector<size_t> collisions_per_meaning(BIT_VECTOR_LENGTH, 0);
GpuVoxelsMapSharedPtr obstacleMapPtr(obstacle);
size_t collisions = sweptVolume->collideCountingPerMeaning(obstacleMapPtr, collisions_per_meaning);
//build string to check all swept volume collisions at once
std::stringstream sstream;
sstream << "(Meaning|Collisions) ";
for (size_t i = 0; i < BIT_VECTOR_LENGTH; i++)
{
if(collisions_per_meaning.at(i) > 0)
{
sstream << "(" << i << "|" << collisions_per_meaning.at(i) << ") ";
}
}
std::string s = sstream.str();
BOOST_CHECK_MESSAGE(sstream.str() == "(Meaning|Collisions) (14|1) (15|8) (16|8) (17|27) (18|27) (19|27) (20|8) (21|1) (22|1) ", "wrong SweptVolume Parts got hit");
BOOST_CHECK_MESSAGE(collisions == 108, "collisions == 108");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("collide_bitvoxellist_with_countingpermeaning_bitvoxellist", "collide_bitvoxellist_with_countingpermeaning_bitvoxellist", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(collide_bitvoxellist_with_prob_voxelmap)
{
PERF_MON_START("collide_bitvoxellist_with_prob_voxelmap");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.f;
BitVectorVoxelList* list = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list->insertMetaPointCloud(boxes, voxel_meanings);
GpuVoxelsMapSharedPtr map_2(new ProbVoxelMap(Vector3ui(dimX, dimY, dimZ), side_length, MT_PROBAB_VOXELMAP));
map_2->insertMetaPointCloud(boxes, eBVM_OCCUPIED);
size_t num_colls = list->collideWith(map_2->as<ProbVoxelMap>(), ProbabilisticVoxel::probabilityToFloat(cSENSOR_MODEL_OCCUPIED));
BOOST_CHECK_MESSAGE(num_colls == 46, "Number of Collisions == 46");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("collide_bitvoxellist_with_prob_voxelmap", "collide_bitvoxellist_with_prob_voxelmap", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_collide_with_types_prob_voxelmap)
{
PERF_MON_START("bitvoxellist_collide_with_types_prob_voxelmap");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.f;
BitVectorVoxelList* list = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list->insertMetaPointCloud(boxes, voxel_meanings);
GpuVoxelsMapSharedPtr map_2(new ProbVoxelMap(Vector3ui(dimX, dimY, dimZ), side_length, MT_PROBAB_VOXELMAP));
map_2->insertMetaPointCloud(boxes, eBVM_OCCUPIED);
BitVectorVoxel types_in_collision;
size_t num_colls = list->collideWithTypes(map_2->as<ProbVoxelMap>(), types_in_collision, 1.0);
BOOST_CHECK_MESSAGE(num_colls == 46, "Number of Collisions == 46");
BOOST_CHECK_MESSAGE(types_in_collision.bitVector().getBit(11) && types_in_collision.bitVector().getBit(12), "Both Types found.");
types_in_collision.bitVector().clearBit(11);
types_in_collision.bitVector().clearBit(12);
BOOST_CHECK_MESSAGE(types_in_collision.bitVector().isZero(), "All other Types are clear.");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_collide_with_types_prob_voxelmap", "bitvoxellist_collide_with_types_prob_voxelmap", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_collide_with_types_bitvoxelmap)
{
PERF_MON_START("bitvoxellist_collide_with_types_bitvoxelmap");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.f;
BitVectorVoxelList* list = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list->insertMetaPointCloud(boxes, voxel_meanings);
GpuVoxelsMapSharedPtr map_2(new BitVectorVoxelMap(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELMAP));
map_2->insertMetaPointCloud(boxes, eBVM_OCCUPIED);
BitVectorVoxel types_in_collision;
size_t num_colls = list->collideWithTypes(map_2->as<BitVectorVoxelMap>(), types_in_collision, 1.0);
BOOST_CHECK_MESSAGE(num_colls == 46, "Number of Collisions == 46");
BOOST_CHECK_MESSAGE(types_in_collision.bitVector().getBit(11) && types_in_collision.bitVector().getBit(12), "Both Types found.");
types_in_collision.bitVector().clearBit(11);
types_in_collision.bitVector().clearBit(12);
BOOST_CHECK_MESSAGE(types_in_collision.bitVector().isZero(), "All other Types are clear.");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_collide_with_types_bitvoxelmap", "bitvoxellist_collide_with_types_bitvoxelmap", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(collide_bitvoxellist_with_prob_voxelmap_shifting)
{
PERF_MON_START("collide_bitvoxellist_with_prob_voxelmap_shifting");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.f;
BitVectorVoxelList* list = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
std::vector<std::vector<Vector3f> > box_cloud;
float delta = 0.1;
box_cloud.push_back(createBoxOfPoints(b1_min, b1_max, delta));
MetaPointCloud box(box_cloud);
box.syncToDevice();
list->insertMetaPointCloud(box, eBVM_OCCUPIED);
GpuVoxelsMapSharedPtr map_2(new ProbVoxelMap(Vector3ui(dimX, dimY, dimZ), side_length, MT_PROBAB_VOXELMAP));
size_t num_colls;
map_2->insertMetaPointCloud(box, eBVM_OCCUPIED);
for(float shift = 0.0; shift < 4.0; shift += 0.5)
{
num_colls = list->collideWith(map_2->as<ProbVoxelMap>(), ProbabilisticVoxel::probabilityToFloat(cSENSOR_MODEL_OCCUPIED), Vector3i(shift, 0,0));
if(shift < 1.0)
BOOST_CHECK_MESSAGE(num_colls == 27, "Number of Collisions == 27");
else if(shift < 2.0)
BOOST_CHECK_MESSAGE(num_colls == 18, "Number of Collisions == 18");
else if(shift < 3.0)
BOOST_CHECK_MESSAGE(num_colls == 9, "Number of Collisions == 9");
else
BOOST_CHECK_MESSAGE(num_colls == 0, "Number of Collisions == 0");
}
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("collide_bitvoxellist_with_prob_voxelmap_shifting", "collide_bitvoxellist_with_prob_voxelmap_shifting", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_insert_metapointcloud)
{
PERF_MON_START("bitvoxellist_insert_metapointcloud");
for(int i = 0; i < iterationCount; i++)
{
// Generate two boxes that each occupie 27 Voxel ==> 54 Voxels.
// They overlap each other by 8 Voxels. ==> 46 Voxels should remain in the list.
// The 8 Voxels that overlap must have set bits of both dense pointcloud meanings!
BitVectorVoxelList* list = new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list->insertMetaPointCloud(boxes, voxel_meanings);
thrust::device_vector<Cube>* d_cubes = NULL;
list->extractCubes(&d_cubes);
thrust::host_vector<Cube> h_cubes = *d_cubes;
BOOST_CHECK_MESSAGE(h_cubes.size() == 46, "Number of reduced cubes == 46");
BitVector<BIT_VECTOR_LENGTH> ref_bv;
ref_bv.setBit(11);
ref_bv.setBit(12);
size_t num_voxels_with_both_bits = 0;
for(size_t i = 0; i < h_cubes.size(); i++)
{
if(h_cubes[i].m_type_vector == ref_bv)
{
num_voxels_with_both_bits++;
//std::cout << "Cube[" << i << "] bitvector: " << h_cubes[i].m_type_vector << std::endl;
//std::cout << "Cube[" << i << "] position: " << h_cubes[i].m_position << std::endl;
bool position_wrong = (h_cubes[i].m_position.x < 1.9 || h_cubes[i].m_position.y < 1.9 || h_cubes[i].m_position.z < 1.9 ||
h_cubes[i].m_position.x > 3.1 || h_cubes[i].m_position.y > 3.1 || h_cubes[i].m_position.z > 3.1);
BOOST_CHECK_MESSAGE(!position_wrong, "Pose of merged voxel-vector in center");
}
}
BOOST_CHECK_MESSAGE(num_voxels_with_both_bits == 8, "Detect 8 overlapping voxels.");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_insert_metapointcloud", "bitvoxellist_insert_metapointcloud", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_findMatchingVoxels)
{
// this test depends on the limits of the voxellist, in part because of voxellist out_of_bounds checking
int dimX = 500;
int dimY = dimX;
int dimZ = 200;
PERF_MON_START("bitvoxellist_findMatchingVoxels");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 0.01;
//create lists
GpuVoxelsMapSharedPtr voxellist1_shrd_ptr(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST));
GpuVoxelsMapSharedPtr voxellist2_shrd_ptr(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST));
//points which are not colliding to bloat the lists
std::vector<Vector3f> box1 = createBoxOfPoints(Vector3f(2.1, 0.1, 5.1), Vector3f(4.9, 4.9, 9.9), 0.02f);
std::vector<Vector3f> box2 = createBoxOfPoints(Vector3f(5.1, 5.1, 10.1), Vector3f(9.9, 9.9, 14.9), 0.3f);
//points actually participating in collision
std::vector<Vector3f> collisionPoints1;
for(int j = 0; j < 40; j++)
{
collisionPoints1.push_back(Vector3f(j / 40.0 * 5.0, 1.0, 1.0));
}
std::vector<Vector3f> collisionPoints2;
for(int j = 0; j < 30; j++)
{
collisionPoints2.push_back(Vector3f(j / 30.0 * 5.0, 2.0, 1.0));
}
std::vector<Vector3f> collisionPoints3;
for(int j = 0; j < 20; j++)
{
collisionPoints3.push_back(Vector3f(j / 20.0 * 5.0, 3.0, 1.0));
}
//insert ==> voxellist1_shrd_ptr will be the list with more entries
voxellist1_shrd_ptr->insertPointCloud(box1, BitVoxelMeaning(10));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints1, BitVoxelMeaning(11));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints2, BitVoxelMeaning(12));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints3, BitVoxelMeaning(13));
voxellist2_shrd_ptr->insertPointCloud(box2, BitVoxelMeaning(20));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints1, BitVoxelMeaning(21));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints2, BitVoxelMeaning(22));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints3, BitVoxelMeaning(23));
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_findMatchingVoxels", "bitvoxellist_findMatchingVoxels::data_generation", "voxellists");
// Now we collide the lists in different orders and verify the result.
// The collision checker internally swaps lists due to performance reasons.
// So we test for if the output contains data from the given input list:
//first collide list1 with list2
size_t num_coll = 0;
std::vector<size_t> collisions_per_meaning(BIT_VECTOR_LENGTH, 0);
num_coll = voxellist1_shrd_ptr->as<BitVectorVoxelList>()->collideCountingPerMeaning(voxellist2_shrd_ptr, collisions_per_meaning);
BOOST_CHECK(num_coll == 90);
BOOST_CHECK(collisions_per_meaning[11] == 40 && collisions_per_meaning[12] == 30 && collisions_per_meaning[13] == 20);
BOOST_CHECK(collisions_per_meaning[21] == 0 && collisions_per_meaning[22] == 0 && collisions_per_meaning[23] == 0);
BOOST_CHECK(collisions_per_meaning[10] == 0 && collisions_per_meaning[20] == 0);
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_findMatchingVoxels", "bitvoxellist_findMatchingVoxels::collision", "voxellists");
//then collide list2 with list1
collisions_per_meaning.assign(BIT_VECTOR_LENGTH, 0);
num_coll = voxellist2_shrd_ptr->as<BitVectorVoxelList>()->collideCountingPerMeaning(voxellist1_shrd_ptr, collisions_per_meaning);
BOOST_CHECK(num_coll == 90);
BOOST_CHECK(collisions_per_meaning[21] == 40 && collisions_per_meaning[22] == 30 && collisions_per_meaning[23] == 20);
BOOST_CHECK(collisions_per_meaning[11] == 0 && collisions_per_meaning[12] == 0 && collisions_per_meaning[13] == 0);
BOOST_CHECK(collisions_per_meaning[10] == 0 && collisions_per_meaning[20] == 0);
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_findMatchingVoxels", "bitvoxellist_findMatchingVoxels::collisionReverse", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_findMatching_omit)
{
// this test depends on the limits of the voxellist, in part because of voxellist out_of_bounds checking
int dimX = 500;
int dimY = dimX;
int dimZ = 200;
PERF_MON_START("bitvoxellist_findMatching_omit");
for(int omit = 0; omit <= 1; omit++)
{
for(int i = 0; i < iterationCount; i++)
{
float side_length = 0.01;
//create lists
GpuVoxelsMapSharedPtr voxellist1_shrd_ptr(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST));
GpuVoxelsMapSharedPtr voxellist2_shrd_ptr(new CountingVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_COUNTING_VOXELLIST));
GpuVoxelsMapSharedPtr matching_shrd_ptr(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST));
//points which are not colliding to bloat the lists
std::vector<Vector3f> box1 = createBoxOfPoints(Vector3f(2.1, 0.1, 5.1), Vector3f(4.9, 4.9, 9.9), 0.02f);
std::vector<Vector3f> box2 = createBoxOfPoints(Vector3f(5.1, 5.1, 10.1), Vector3f(9.9, 9.9, 14.9), 0.3f);
//points actually participating in collision
std::vector<Vector3f> collisionPoints1;
for(int j = 0; j < 40; j++)
{
collisionPoints1.push_back(Vector3f(j / 40.0 * 5.0, 1.0, 1.0));
}
std::vector<Vector3f> collisionPoints2;
for(int j = 0; j < 30; j++)
{
collisionPoints2.push_back(Vector3f(j / 30.0 * 5.0, 2.0, 1.0));
}
std::vector<Vector3f> collisionPoints3;
for(int j = 0; j < 20; j++)
{
collisionPoints3.push_back(Vector3f(j / 20.0 * 5.0, 3.0, 1.0));
}
//insert ==> voxellist1_shrd_ptr will be the list with more entries
voxellist1_shrd_ptr->insertPointCloud(box1, BitVoxelMeaning(10));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints1, BitVoxelMeaning(11));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints2, BitVoxelMeaning(12));
voxellist1_shrd_ptr->insertPointCloud(collisionPoints3, BitVoxelMeaning(13));
voxellist2_shrd_ptr->insertPointCloud(box2, BitVoxelMeaning(20));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints1, BitVoxelMeaning(21));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints2, BitVoxelMeaning(22));
voxellist2_shrd_ptr->insertPointCloud(collisionPoints3, BitVoxelMeaning(23));
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_findMatching_omit", "bitvoxellist_findMatching_omit::data_generation", "voxellists");
// Now we collide the lists in different orders and verify the result.
// The collision checker internally swaps lists due to performance reasons.
// So we test for if the output contains data from the given input list:
gpu_voxels::Vector3i offset;
voxellist1_shrd_ptr->as<voxellist::BitVectorVoxelList>()->findMatchingVoxels(
voxellist2_shrd_ptr->as<voxellist::CountingVoxelList>(),
offset,
matching_shrd_ptr->as<voxellist::BitVectorVoxelList>(),
omit // don't omit coords
);
//first collide list1 with list2
size_t num_coll = matching_shrd_ptr->as<voxellist::BitVectorVoxelList>()->getDimensions().x;
BOOST_CHECK(num_coll == 90);
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_findMatching_omit", "bitvoxellist_findMatching_omit::collision", "voxellists");
}
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_bitshift_collision)
{
PERF_MON_START("bitvoxellist_bitshift_collision");
for(int i = 0; i < iterationCount; i++)
{
float side_length = 1.f;
BitVectorVoxelList map_1(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST);
GpuVoxelsMapSharedPtr map_2(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), side_length, MT_BITVECTOR_VOXELLIST));
BitVectorVoxelList* map2_base_ptr = dynamic_cast<BitVectorVoxelList*>(map_2.get());
std::vector<Vector3f> points;
points.push_back(Vector3f(0.3,0.3,0.3));
uint32_t shift_size = 0;
const uint32_t shift_start = 50;
const uint32_t type_int = eBVM_SWEPT_VOLUME_START + shift_start;
const BitVoxelMeaning type_2 = BitVoxelMeaning(type_int);
while (shift_size < shift_start + eBVM_SWEPT_VOLUME_START - 5)
{
map_1.clearMap();
map_2->clearMap();
map_2->insertPointCloud(points, type_2);
const BitVoxelMeaning type_1 = BitVoxelMeaning(type_int - shift_size);
map_1.insertPointCloud(points, type_1);
map2_base_ptr->shiftLeftSweptVolumeIDs(shift_size);
size_t num_collisions = 0;
BitVectorVoxel types_voxel;
size_t window_size = 1;
num_collisions = map_1.collideWithBitcheck(map_2->as<voxellist::BitVectorVoxelList>(), window_size);
if (shift_size <= shift_start)
{
BOOST_CHECK(num_collisions == 1);
}
else
{
BOOST_CHECK(num_collisions == 0);
}
shift_size++;
}
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_bitshift_collision", "bitvoxellist_bitshift_collision", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(voxellist_equals_function)
{
PERF_MON_START("voxellist_equals_function");
for(int i = 0; i < iterationCount; i++)
{
BitVectorVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
BitVectorVoxelList list2(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
std::vector<Vector3f> outliers;
outliers.push_back(Vector3f(9.22, 9.22, 9.22));
list1.insertMetaPointCloud(boxes, voxel_meanings);
list2.insertMetaPointCloud(boxes, voxel_meanings);
BOOST_CHECK_MESSAGE(list1.equals(list2), "Lists are equal.");
list1.insertPointCloud(outliers, BitVoxelMeaning(11));
list2.insertPointCloud(outliers, BitVoxelMeaning(12));
BOOST_CHECK_MESSAGE(!list1.equals(list2), "Lists differ.");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("voxellist_equals_function", "voxellist_equals_function", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(voxellist_disk_io)
{
PERF_MON_START("voxellist_disk_io");
for(int i = 0; i < iterationCount; i++)
{
BitVectorVoxelList list(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 0.1;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list.insertMetaPointCloud(boxes, voxel_meanings);
list.writeToDisk("temp_list.lst");
BitVectorVoxelList list2(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
list2.readFromDisk("temp_list.lst");
BOOST_CHECK_MESSAGE(list.equals(list2), "List from Disk equals original list.");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("voxellist_disk_io", "voxellist_disk_io", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitvoxellist_subtract)
{
PERF_MON_START("bitvoxellist_subtract");
for(int i = 0; i < iterationCount; i++)
{
// Generate two boxes that each occupie 27 Voxel.
// They overlap each other by 8 Voxels. Subtract them. ==> 19 Voxels should remain in the list.
BitVectorVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
BitVectorVoxelList list2(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
float delta = 0.1;
std::vector<Vector3f> box_cloud1 = createBoxOfPoints(b1_min, b1_max, delta);
std::vector<Vector3f> box_cloud2 = createBoxOfPoints(b2_min, b2_max, delta);
list1.insertPointCloud(box_cloud1, BitVoxelMeaning(11));
list2.insertPointCloud(box_cloud2, BitVoxelMeaning(12));
list1.subtract(&list2, Vector3f());
thrust::device_vector<Cube>* d_cubes = NULL;
list1.extractCubes(&d_cubes);
thrust::host_vector<Cube> h_cubes = *d_cubes;
BOOST_CHECK_MESSAGE(h_cubes.size() == 19, "Number of cubes after subtract == 19");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitvoxellist_subtract", "bitvoxellist_subtract", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_collide_bitvectorvoxellist_minimal)
{
PERF_MON_START("countingvoxellist_collide_bitvectorvoxellist_minimal");
for (int i = 0; i < iterationCount; i++)
{
CountingVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_COUNTING_VOXELLIST);
Vector3f testPoint1(1.1, 1.1, 1.1);
Vector3f testPoint2(1.1, 1.1, 1.2);
Vector3f testPoint3(3.0, 3.0, 3.0);
std::vector<Vector3f> cloud;
cloud.push_back(testPoint1);
cloud.push_back(testPoint2);
cloud.push_back(testPoint3);
std::vector<std::vector<Vector3f> > clouds;
clouds.push_back(cloud);
MetaPointCloud points(clouds);
points.syncToDevice();
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
list1.insertMetaPointCloud(points, voxel_meanings);
GpuVoxelsMapSharedPtr map_2(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST));
map_2->insertMetaPointCloud(points, eBVM_OCCUPIED);
size_t num_colls1 = list1.collideWith(map_2->as<BitVectorVoxelList>(), 1.0);
size_t num_colls2 = list1.collideWith(map_2->as<BitVectorVoxelList>(), 2.0);
BOOST_CHECK_MESSAGE(num_colls1 == 2, "Number of Collisions1 == 2");
BOOST_CHECK_MESSAGE(num_colls2 == 1, "Number of Collisions2 == 1");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("countingvoxellist_collide_bitvectorvoxellist_minimal", "countingvoxellist_collide_bitvectorvoxellist_minimal", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_collide_bitvectorvoxellist)
{
PERF_MON_START("countingvoxellist_collide_bitvectorvoxellist");
for (int i = 0; i < iterationCount; i++)
{
CountingVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_COUNTING_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
std::vector<BitVoxelMeaning> voxel_meanings;
voxel_meanings.push_back(BitVoxelMeaning(11));
voxel_meanings.push_back(BitVoxelMeaning(12));
std::vector<std::vector<Vector3f> > box_clouds;
float delta = 1.0f;
box_clouds.push_back(createBoxOfPoints(b1_min, b1_max, delta));
box_clouds.push_back(createBoxOfPoints(b2_min, b2_max, delta));
// for (int i=0; i<box_clouds.size(); i++) {
// std::cout << "start vector " << std::endl;
// for (int j=0; j<box_clouds[i].size(); j++) {
// std::cout << box_clouds[i][j] << std::endl;
// }
// }
MetaPointCloud boxes(box_clouds);
boxes.syncToDevice();
list1.insertMetaPointCloud(boxes, voxel_meanings);
GpuVoxelsMapSharedPtr map_2(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST));
map_2->insertMetaPointCloud(boxes, eBVM_OCCUPIED);
// //DEBUG
// list1.screendump(true);
// map_2->as<BitVectorVoxelList>()->screendump(true);
size_t num_colls = list1.collideWith(map_2->as<BitVectorVoxelList>(), 1.0);
// //DEBUG
// list1.screendump(true);
// map_2->as<BitVectorVoxelList>()->screendump(true);
BOOST_CHECK_MESSAGE(num_colls == 46, "Number of Collisions == 46");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("countingvoxellist_collide_bitvectorvoxellist", "countingvoxellist_collide_bitvectorvoxellist", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_subtract_bitvectorvoxellist_minimal)
{
PERF_MON_START("countingvoxellist_subtract_bitvectorvoxellist_minimal");
for (int i = 0; i < iterationCount; i++)
{
GpuVoxelsMapSharedPtr list1(new CountingVoxelList(Vector3ui(dimX, dimY, dimZ), 1, MT_COUNTING_VOXELLIST));
GpuVoxelsMapSharedPtr list2(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST));
Vector3f testPoint1(1.1, 1.1, 1.1);
Vector3f testPoint2(1.2, 1.1, 1.1);
Vector3f testPoint3(3.1, 3.1, 3.1);
Vector3f testPoint4(5.0, 5.0, 5.0);
std::vector<Vector3f> cloud1;
cloud1.push_back(testPoint1);
cloud1.push_back(testPoint2);
cloud1.push_back(testPoint3);
cloud1.push_back(testPoint4);
std::vector<Vector3f> cloud2;
cloud2.push_back(testPoint1);
cloud2.push_back(testPoint3);
list1->insertPointCloud(cloud1, BitVoxelMeaning(11));
list2->insertPointCloud(cloud2, BitVoxelMeaning(12));
list1->as<CountingVoxelList>()->subtractFromCountingVoxelList(list2->as<BitVectorVoxelList>(), Vector3f());
thrust::device_vector<Cube> *d_cubes = NULL;
list1->as<CountingVoxelList>()->extractCubes(&d_cubes);
thrust::host_vector<Cube> h_cubes = *d_cubes;
BOOST_CHECK_MESSAGE(h_cubes.size() == 1, "Number of cubes after subtract == 1 ");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("countingvoxellist_subtract_bitvectorvoxellist_minimal", "countingvoxellist_subtract_bitvectorvoxellist_minimal", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_merge_into_bitvectorvoxellist_minimal)
{
PERF_MON_START("countingvoxellist_merge_into_bitvectorvoxellist_minimal");
for (int i = 0; i < iterationCount; i++)
{
GpuVoxelsMapSharedPtr list1(new CountingVoxelList(Vector3ui(dimX, dimY, dimZ), 0.1f, MT_COUNTING_VOXELLIST));
GpuVoxelsMapSharedPtr list2(new BitVectorVoxelList(Vector3ui(dimX, dimY, dimZ), 0.1f, MT_BITVECTOR_VOXELLIST));
Vector3f testPoint1(1.1, 1.1, 1.1);
Vector3f testPoint2(1.2, 1.1, 1.1);
Vector3f testPoint3(3.1, 3.1, 3.1);
Vector3f testPoint4(5.0, 5.0, 5.0);
std::vector<Vector3f> cloud1;
cloud1.push_back(testPoint1);
cloud1.push_back(testPoint2);
cloud1.push_back(testPoint4);
std::vector<Vector3f> cloud2;
cloud2.push_back(testPoint1);
cloud2.push_back(testPoint3);
list1->insertPointCloud(cloud1, BitVoxelMeaning(11));
list2->insertPointCloud(cloud2, BitVoxelMeaning(12));
BitVoxelMeaning bvm = eBVM_OCCUPIED;
list2->merge(list1, Vector3f(), &bvm);
// list2->as<BitVectorVoxelList>()->screendump(true); //DEBUG
thrust::device_vector<Cube> *d_cubes = NULL;
list2->as<BitVectorVoxelList>()->extractCubes(&d_cubes);
thrust::host_vector<Cube> h_cubes = *d_cubes;
BOOST_CHECK_MESSAGE(h_cubes.size() == 4, "Number of cubes after merge == 4 ");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("countingvoxellist_merge_into_bitvectorvoxellist_minimal", "countingvoxellist_merge_into_bitvectorvoxellist_minimal", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_subtract_bitvectorvoxellist)
{
PERF_MON_START("countingvoxellist_subtract_bitvectorvoxellist");
for (int i = 0; i < iterationCount; i++)
{
CountingVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_COUNTING_VOXELLIST);
// BitVectorVoxelList list1(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
BitVectorVoxelList list2(Vector3ui(dimX, dimY, dimZ), 1, MT_BITVECTOR_VOXELLIST);
Vector3f b1_min(1.1,1.1,1.1);
Vector3f b1_max(3.9,3.9,3.9);
Vector3f b2_min(2.1,2.1,2.1);
Vector3f b2_max(4.9,4.9,4.9);
float delta = 0.1;
std::vector<Vector3f> box_cloud1 = createBoxOfPoints(b1_min, b1_max, delta);
std::vector<Vector3f> box_cloud2 = createBoxOfPoints(b2_min, b2_max, delta);
list1.insertPointCloud(box_cloud1, BitVoxelMeaning(11));
list2.insertPointCloud(box_cloud2, BitVoxelMeaning(12));
//list1.subtract(&list2, Vector3f());
list1.subtractFromCountingVoxelList(&list2, Vector3f());
thrust::device_vector<Cube>* d_cubes = NULL;
list1.extractCubes(&d_cubes);
thrust::host_vector<Cube> h_cubes = *d_cubes;
BOOST_CHECK_MESSAGE(h_cubes.size() == 19, "Number of cubes after subtract == 19");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("countingvoxellist_subtract_bitvectorvoxellist", "countingvoxellist_subtract_bitvectorvoxellist", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(bitmasked_collision)
{
PERF_MON_START("bitmasked_collision");
for(int i = 0; i < iterationCount; i++)
{
/*
* Generate three boxes that each occupie 64 Voxel. They lie along the X-axis next to each other and overlap with their neighbour by 16 Voxels.
* Generate another bigger box that intersects with the three smaller boxes about 2 rows on the Y-axis (72 Voxels intersecting).
*
*
* Voxellist: Voxelmap:
* / = Type 1 o = Occupied
* \ = Type 2
* X = Type 1&2
* y y
* ^ ^
* | |
* | --------------- |
* | |/|/|X|\|X|/|/| |
* | --------------- |
* | |/|/|X|\|X|/|/| |
* | --------------- | ---------------
* | |/|/|X|\|X|/|/| | |o|o|o|o|o|o|o|
* | --------------- | ---------------
* | | |o|o|o|o|o|o|o|
* | | ---------------
* | | |o|o|o|o|o|o|o|
* | | ---------------
* ----------------------> x ----------------------> x
*
*/
// ==> To get some more CUDA Blocks involved,
// we have to scale down the voxelsize to 1/4 ==> Voxels in collision * 64
BitVectorVoxelList list(Vector3ui(dimX, dimY, dimZ), 0.025, MT_BITVECTOR_VOXELLIST);
ProbVoxelMap map(Vector3ui(dimX, dimY, dimZ), 0.025, MT_PROBAB_VOXELMAP);
float delta = 0.005;
Vector3f b_min(0.111,0.111,0.111);
Vector3f b_max(0.799,0.399,0.399);
std::vector<Vector3f> box_cloud = createBoxOfPoints(b_min, b_max, delta);
map.insertPointCloud(box_cloud, gpu_voxels::eBVM_OCCUPIED);
b_min = Vector3f(0.111,0.311,0.111);
b_max = Vector3f(0.399,0.599,0.399);
box_cloud = createBoxOfPoints(b_min, b_max, delta);
list.insertPointCloud(box_cloud, gpu_voxels::BitVoxelMeaning(34));
b_min = Vector3f(0.311,0.311,0.111);
b_max = Vector3f(0.599,0.599,0.399);
box_cloud = createBoxOfPoints(b_min, b_max, delta);
list.insertPointCloud(box_cloud, gpu_voxels::BitVoxelMeaning(63));
b_min = Vector3f(0.511,0.311,0.111);
b_max = Vector3f(0.799,0.599,0.399);
box_cloud = createBoxOfPoints(b_min, b_max, delta);
list.insertPointCloud(box_cloud, gpu_voxels::BitVoxelMeaning(102));
size_t num_colls;
BitVectorVoxel types_to_check;
// No offset given:
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f);
BOOST_CHECK_MESSAGE(num_colls == 0, "Zero collisions expected");
types_to_check.bitVector().setBit(33);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f);
BOOST_CHECK_MESSAGE(num_colls == 0, "Zero collisions expected");
types_to_check.bitVector().setBit(34);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f);
BOOST_CHECK_MESSAGE(num_colls == 9*64, "9*64 collisions expected");
types_to_check.bitVector().setBit(63);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f);
BOOST_CHECK_MESSAGE(num_colls == 15*64, "15*64 collisions expected");
types_to_check.bitVector().setBit(102);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f);
BOOST_CHECK_MESSAGE(num_colls == 21*64, "21*64 collisions expected");
// Offset shifting List on Y-Axis into Map:
Vector3i offset(0,-4,0);
types_to_check.bitVector().clear();
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 0, "Shift (0 -4 0): Zero collisions expected");
types_to_check.bitVector().setBit(33);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 0, "Shift (0 -4 0): Zero collisions expected");
types_to_check.bitVector().setBit(34);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 18*64, "Shift (0 -4 0): 18*64 collisions expected");
types_to_check.bitVector().setBit(63);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 30*64, "Shift (0 -4 0): 30*64 collisions expected");
types_to_check.bitVector().setBit(102);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 42*64, "Shift (0 -4 0): 42*64 collisions expected");
// Offset shifting List on Y-Axis into Map and on Z out of map
offset = Vector3i(0,-4,-4);
types_to_check.bitVector().clear();
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 0, "Shift (0 -4 -4): Zero collisions expected");
types_to_check.bitVector().setBit(33);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 0, "Shift (0 -4 -4): Zero collisions expected");
types_to_check.bitVector().setBit(34);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 12*64, "Shift (0 -4 -4): 12*64 collisions expected");
types_to_check.bitVector().setBit(63);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 20*64, "Shift (0 -4 -4): 24*64 collisions expected");
types_to_check.bitVector().setBit(102);
num_colls = list.collideWithTypeMask(&map, types_to_check, 1.0f, offset);
BOOST_CHECK_MESSAGE(num_colls == 28*64, "Shift (0 -4 -4): 36*64 collisions expected");
PERF_MON_SILENT_MEASURE_AND_RESET_INFO_P("bitmasked_collision", "bitmasked_collision", "voxellists");
}
}
BOOST_AUTO_TEST_CASE(countingvoxellist_remove_underpopulated)
{
PERF_MON_START("countingvoxellist_remove_underpopulated");
std::vector<Vector3f> listPoints;
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.5f));
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.4f));
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.4f));
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.3f));
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.3f));
listPoints.push_back(Vector3f(0.2f, 0.7f, 0.3f));