-
Notifications
You must be signed in to change notification settings - Fork 8
/
Copy pathreactive_planner_lib.cpp
executable file
·2447 lines (2105 loc) · 191 KB
/
reactive_planner_lib.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
// MIT License (modified)
// Copyright (c) 2020 The Trustees of the University of Pennsylvania
// Authors:
// Vasileios Vasilopoulos <[email protected]>
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this **file** (the "Software"), to deal
// in the Software without restriction, including without limitation the rights
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
// copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
// The above copyright notice and this permission notice shall be included in all
// copies or substantial portions of the Software.
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
// SOFTWARE.
#include <reactive_planner_lib.h>
// Define properties for dilations
const int points_per_circle = 5;
bg::strategy::buffer::join_round join_strategy(points_per_circle);
bg::strategy::buffer::end_flat end_strategy;
bg::strategy::buffer::point_circle circle_strategy;
bg::strategy::buffer::side_straight side_strategy;
std::vector<double> linspace(double a, double b, uint16_t n) {
std::vector<double> array;
double step = (b-a) / (n-1);
array.push_back(a);
while(array.size() < n) {
a += step; // could recode to better handle rounding errors
array.push_back(a);
}
array.pop_back();
array.push_back(b);
return array;
}
void completeLIDAR2D(LIDARClass* LIDAR) {
/**
* Function that completes missing LIDAR data due to limited field of view
*
* Input:
* 1) LIDAR: Incomplete LIDAR object
*/
if ((LIDAR->MaxAngle-LIDAR->MinAngle) < 6.28) {
std::vector<double> tempR = LIDAR->RangeMeasurements;
std::vector<double> tempAngle = LIDAR->Angle;
double tempResolution = LIDAR->Resolution;
// Updated LIDAR model
LIDAR->MinAngle = -M_PI;
LIDAR->MaxAngle = LIDAR->MinAngle + 2.0*M_PI;
LIDAR->NumSample = uint16_t(round((2.0*M_PI/tempResolution)+1));
LIDAR->Resolution = (LIDAR->MaxAngle-LIDAR->MinAngle)/(LIDAR->NumSample-1);
LIDAR->Angle = linspace(LIDAR->MinAngle, LIDAR->MaxAngle, LIDAR->NumSample);
// Completed Range Data
std::vector<double> R(LIDAR->NumSample, LIDAR->Range);
for (size_t i = 0 ; i < tempAngle.size() ; i++) {
size_t index = size_t(roundf((fmod(tempAngle[i]-LIDAR->MinAngle+LIDAR->Resolution/2.0,2.0*M_PI))/LIDAR->Resolution));
R[index] = tempR[i];
}
LIDAR->RangeMeasurements.assign(R.begin(), R.end());
}
return;
}
void constructLIDAR2D(const sensor_msgs::LaserScan::ConstPtr& DataLIDAR, double CutoffRange, double AllowableRange, double Pitch, LIDARClass *LIDAR) {
/**
* Function that constructs a LIDAR object to be used by the reactive planner
*
* Input:
* 1) DataLIDAR: Received LIDAR data
* 2) CutoffRange: Cutoff range below which the range measurement is ignored
* 3) AllowableRange: Maximum allowable LIDAR range
* 4) Pitch: Robot pitch to be considered for range compensation (default is 0)
* 5) LIDAR: Constructed LIDAR object
*
*/
// LIDAR operations
double Range = AllowableRange;
double Infinity = AllowableRange;
double MinAngle = double(DataLIDAR->angle_min);
double MaxAngle = double(DataLIDAR->angle_max);
double Resolution = double(DataLIDAR->angle_increment);
double NumSample = DataLIDAR->ranges.size();
std::vector<double> Angle = linspace(MinAngle, MaxAngle, NumSample);
Resolution = Angle[1]-Angle[0];
std::vector<double> RangeMeasurements(DataLIDAR->ranges.begin(), DataLIDAR->ranges.end());
for (size_t i = 0; i < RangeMeasurements.size() ; i++) {
// Project on the robot plane
RangeMeasurements[i] = std::min(RangeMeasurements[i]*cos(Pitch), AllowableRange);
// Reject NaNs
if (isnan(RangeMeasurements[i])) {
RangeMeasurements[i] = Infinity;
}
// Apply cutoff range
if (RangeMeasurements[i] <= CutoffRange) {
RangeMeasurements[i] = Infinity;
}
}
// Construct LIDAR object
LIDAR->RangeMeasurements = RangeMeasurements;
LIDAR->Range = Range;
LIDAR->Infinity = Infinity;
LIDAR->MinAngle = MinAngle;
LIDAR->MaxAngle = MaxAngle;
LIDAR->Resolution = Resolution;
LIDAR->NumSample = NumSample;
LIDAR->Angle = Angle;
return;
}
std::vector<point> obstaclePointsLIDAR2D(point RobotPosition, double RobotOrientation, LIDARClass* LIDAR) {
/**
* Function that returns the coordinates of observed obstacle points from the LIDAR
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) LIDAR: Current LIDAR object
*
* Output:
* 1) PointsAll: Coordinates of the observed obstacle points from the LIDAR
*/
// Find observed LIDAR points coordinates
std::vector<point> PointsAll(LIDAR->RangeMeasurements.size());
for (size_t i = 0 ; i < LIDAR->RangeMeasurements.size() ; i++) {
point new_point(RobotPosition.get<0>()+LIDAR->RangeMeasurements[i]*cos(LIDAR->Angle[i]+RobotOrientation), RobotPosition.get<1>()+LIDAR->RangeMeasurements[i]*sin(LIDAR->Angle[i]+RobotOrientation));
PointsAll[i] = new_point;
}
return PointsAll;
}
void compensateObstacleLIDAR2D(point RobotPosition, double RobotOrientation, polygon Obstacle, LIDARClass* LIDAR) {
/**
* Function that checks if the LIDAR hits a specific obstacle whose polygon is known
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) Obstacle: shapely.geometry.Polygon obstacle defining the polygonal obstacle
* 4) LIDAR: Current LIDAR object
*/
// Find the indices that correspond to a LIDAR range less than the maximum range
for (size_t i = 0 ; i < LIDAR->RangeMeasurements.size() ; i++) {
if (bg::within(point(RobotPosition.get<0>()+LIDAR->RangeMeasurements[i]*cos(LIDAR->Angle[i]+RobotOrientation), RobotPosition.get<1>()+LIDAR->RangeMeasurements[i]*sin(LIDAR->Angle[i]+RobotOrientation)), Obstacle)) {
LIDAR->RangeMeasurements[i] = LIDAR->Range;
}
}
return;
}
void readLIDAR2D(point RobotPosition, double RobotOrientation, std::vector<polygon> Obstacles, double Range, double MinAngle, double MaxAngle, uint16_t NumSample, LIDARClass *virtualLIDAR) {
/**
* Function that generates a virtual LIDAR object, based on the position of the robot and the surrounding obstacles
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) Obstacles: shapely.geometry.Polygon obstacle array defining the polygonal obstacles
* 4) Range: Range of the LIDAR object to be generated
* 5) MinAngle: Minimum angle of the LIDAR object to be generated
* 6) MaxAngle: Maximum angle of the LIDAR object to be generated
* 7) NumSample: Number of samples used in the process
* 8) virtualLIDAR: Complete virtual LIDAR object
*
*/
// Create a dummy origin
point origin(0.0, 0.0);
// Initialize LIDAR object
double Resolution = (MaxAngle-MinAngle)/(NumSample-1);
std::vector<double> RangeMeasurements(NumSample, Range);
double Infinity = Range + 20.0;
virtualLIDAR->RangeMeasurements = RangeMeasurements;
virtualLIDAR->Range = Range;
virtualLIDAR->Infinity = Infinity;
virtualLIDAR->MinAngle = MinAngle;
virtualLIDAR->MaxAngle = MaxAngle;
virtualLIDAR->Resolution = Resolution;
// Find transform
bg::strategy::transform::matrix_transformer<double, 2, 2> frame_transform(cos(RobotOrientation), -sin(RobotOrientation), RobotPosition.get<0>(),
sin(RobotOrientation), cos(RobotOrientation), RobotPosition.get<1>(),
0.0, 0.0, 1.0);
bg::strategy::transform::inverse_transformer<double, 2, 2> frame_transform_inv(frame_transform);
// Determine distance to the workspace boundary and obstacles
for (size_t co = 0 ; co < Obstacles.size() ; co++) {
// Obstacle in the local sensor frame
std::vector<point> obstacle_points = BoostPolyToBoostPoint(Obstacles[co]);
// Bring the obstacle to the sensor frame
for (size_t i = 0; i < obstacle_points.size(); i++) {
point output_1;
bg::transform(obstacle_points[i], output_1, frame_transform_inv);
obstacle_points[i].set<0>(output_1.get<0>());
obstacle_points[i].set<1>(output_1.get<1>());
}
// Compute distance to every obstacle edge
for (size_t cv = 0; cv < obstacle_points.size(); cv++) {
size_t cn = (cv+1)%(obstacle_points.size());
point vc = obstacle_points[cv];
point vn = obstacle_points[cn];
// Compute the distance to the origin
double dist = std::min(bg::distance(vc, origin), bg::distance(vn, origin));
double w = (vn.get<0>()*(vn.get<0>()-vc.get<0>()) + vn.get<1>()*(vn.get<1>()-vc.get<1>()))/pow(bg::distance(vn,vc),2.0);
if (w>=0.0 && w<=1.0) {
point vx(w*vc.get<0>() + (1-w)*vn.get<0>(), w*vc.get<1>() + (1-w)*vn.get<1>());
dist = std::min(dist, bg::distance(vx, origin));
}
double ac = atan2(vc.get<1>(), vc.get<0>());
double an = atan2(vn.get<1>(), vn.get<0>());
bool flagDist = (dist <= virtualLIDAR->Range);
bool flagAngle = (std::min(ac,an) <= virtualLIDAR->MaxAngle) && (std::max(ac,an) >= virtualLIDAR->MinAngle);
// Compute LIDAR range if the obstacle segment is in the sensing region
if (flagDist && flagAngle) {
// Closest LIDAR ray index
size_t I = size_t(round((std::max(ac,virtualLIDAR->MinAngle)-virtualLIDAR->MinAngle)/virtualLIDAR->Resolution));
I = (I%virtualLIDAR->NumSample);
// Compute the intersection of the LIDAR ray with the sensor footprint
point vtemp(cos(virtualLIDAR->Angle[I]), sin(virtualLIDAR->Angle[I]));
point vRtemp(-sin(virtualLIDAR->Angle[I]), cos(virtualLIDAR->Angle[I]));
double w = -bg::dot_product(vn,vRtemp)/bg::dot_product(point(vc.get<0>()-vn.get<0>(), vc.get<1>()-vn.get<1>()),vRtemp);
if (w>=0.0 && w<=1.0) {
point xtemp(w*vc.get<0>()+(1-w)*vn.get<0>(), w*vc.get<1>()+(1-w)*vn.get<1>());
if (bg::dot_product(xtemp,vtemp) >= 0.0) {
virtualLIDAR->RangeMeasurements[I] = std::min(virtualLIDAR->RangeMeasurements[I], bg::distance(xtemp,origin));
}
}
// Compute the intersection of adjacent LIDAR rays
size_t J = ((I+1)%virtualLIDAR->NumSample);
bool flagValid = true;
while (flagValid && (J != I)) {
point vtemp(cos(virtualLIDAR->Angle[J]), sin(virtualLIDAR->Angle[J]));
point vRtemp(-sin(virtualLIDAR->Angle[J]), cos(virtualLIDAR->Angle[J]));
double w = -bg::dot_product(vn,vRtemp)/bg::dot_product(point(vc.get<0>()-vn.get<0>(), vc.get<1>()-vn.get<1>()),vRtemp);
if (w>=0.0 && w<=1.0) {
point xtemp(w*vc.get<0>()+(1-w)*vn.get<0>(), w*vc.get<1>()+(1-w)*vn.get<1>());
if (bg::dot_product(xtemp,vtemp) >= 0.0) {
virtualLIDAR->RangeMeasurements[J] = std::min(virtualLIDAR->RangeMeasurements[J], bg::distance(xtemp,origin));
J = ((J+1)%virtualLIDAR->NumSample);
} else {
flagValid = false;
}
} else {
flagValid = false;
}
}
J = (static_cast<int>(virtualLIDAR->NumSample) + (static_cast<int>(I-1))%(static_cast<int>(virtualLIDAR->NumSample)))%(static_cast<int>(virtualLIDAR->NumSample));
flagValid = true;
while (flagValid && (J != I)) {
point vtemp(cos(virtualLIDAR->Angle[J]), sin(virtualLIDAR->Angle[J]));
point vRtemp(-sin(virtualLIDAR->Angle[J]), cos(virtualLIDAR->Angle[J]));
double w = -bg::dot_product(vn,vRtemp)/bg::dot_product(point(vc.get<0>()-vn.get<0>(), vc.get<1>()-vn.get<1>()),vRtemp);
if (w>=0.0 && w<=1.0) {
point xtemp(w*vc.get<0>()+(1-w)*vn.get<0>(), w*vc.get<1>()+(1-w)*vn.get<1>());
if (bg::dot_product(xtemp,vtemp) >= 0.0) {
virtualLIDAR->RangeMeasurements[J] = std::min(virtualLIDAR->RangeMeasurements[J], bg::distance(xtemp,origin));
J = (static_cast<int>(virtualLIDAR->NumSample) + (static_cast<int>(J-1))%(static_cast<int>(virtualLIDAR->NumSample)))%(static_cast<int>(virtualLIDAR->NumSample));
} else {
flagValid = false;
}
} else {
flagValid = false;
}
}
}
}
}
return;
}
void translateLIDAR2D(point RobotPosition, double RobotOrientation, point RobotPositionTransformed, double RobotOrientationTransformed, double RobotRadius, LIDARClass* LIDAR) {
/**
* Rebase LIDAR readings from RobotState to RobotStateTransformed
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) RobotPositionTransformed: Transformed robot position
* 4) RobotOrientationTransformed: Transformed robot orientation
* 5) RobotRadius: Robot radius
* 6) LIDAR: Current LIDAR object
*
*/
// Create a dummy origin
point origin(0.0, 0.0);
// Account for the robot radius
for (auto& element: LIDAR->RangeMeasurements) element = element-RobotRadius;
// Find obstacle points
std::vector<point> obstacle_points = obstaclePointsLIDAR2D(RobotPosition, RobotOrientation, LIDAR);
// Find transform
bg::strategy::transform::matrix_transformer<double, 2, 2> frame_transform(cos(RobotOrientationTransformed), -sin(RobotOrientationTransformed), RobotPositionTransformed.get<0>(),
sin(RobotOrientationTransformed), cos(RobotOrientationTransformed), RobotPositionTransformed.get<1>(),
0.0, 0.0, 1.0);
bg::strategy::transform::inverse_transformer<double, 2, 2> frame_transform_inv(frame_transform);
// Apply rotations and translations to find the equivalent distance
std::vector<double> ranges(obstacle_points.size(), LIDAR->Range);
std::vector<double> bearings(obstacle_points.size());
for (size_t i = 0 ; i < obstacle_points.size() ; i++) {
point output_1, output_2;
bg::transform(obstacle_points[i], output_1, frame_transform_inv);
ranges[i] = std::min(bg::distance(output_1, origin),LIDAR->Range);
bearings[i] = atan2(output_1.get<1>(), output_1.get<0>());
}
// Correspond new ranges to the old angles to keep LIDAR properties the same
std::vector<double> R(LIDAR->Angle.size());
for (size_t i = 0 ; i < LIDAR->Angle.size() ; i++) {
std::vector<double> inner_products(bearings.size());
for (size_t j = 0 ; j < bearings.size() ; j++) {
inner_products[j] = cos(bearings[j])*cos(LIDAR->Angle[i]) + sin(bearings[j])*sin(LIDAR->Angle[i]);
}
size_t des_index = std::distance(inner_products.begin(), std::max_element(inner_products.begin(), inner_products.end()));
R[i] = std::min(ranges[des_index], LIDAR->Range);
}
// Update LIDAR object
LIDAR->RangeMeasurements = R;
return;
}
std::vector<bool> localminLIDAR2D(LIDARClass* LIDAR) {
/**
* Function that finds the indices of local minima of the LIDAR range data
*
* Input:
* 1) LIDAR: Current LIDAR object
*
* Output:
* 1) Imin: Indices of local minima of the LIDAR range data
*/
// Vectors used for comparison
std::vector<double> Rp;
std::vector<double> Rn;
// Compute the indices of strictly local minima of the LIDAR range data
if ((LIDAR->MaxAngle-LIDAR->MinAngle)<2.0*M_PI) {
// Assume that the region outside the angular range of LIDAR is free
Rp.push_back(LIDAR->Range);
Rp.insert(Rp.begin()+1, LIDAR->RangeMeasurements.begin(), LIDAR->RangeMeasurements.end()-1);
Rn.insert(Rn.begin(), LIDAR->RangeMeasurements.begin()+1, LIDAR->RangeMeasurements.end());
Rn.push_back(LIDAR->Range);
} else {
Rp.push_back(LIDAR->RangeMeasurements[LIDAR->RangeMeasurements.size()-2]);
Rp.insert(Rp.begin()+1, LIDAR->RangeMeasurements.begin(), LIDAR->RangeMeasurements.end()-1);
Rn.insert(Rn.begin(), LIDAR->RangeMeasurements.begin()+1, LIDAR->RangeMeasurements.end());
Rn.push_back(LIDAR->RangeMeasurements[1]);
}
// Logical tests
std::vector<bool> Imin(LIDAR->RangeMeasurements.size(), false);
for (size_t i = 0; i < LIDAR->RangeMeasurements.size(); i++) {
if (((LIDAR->RangeMeasurements[i]<=Rp[i]) && (LIDAR->RangeMeasurements[i]<Rn[i])) || ((LIDAR->RangeMeasurements[i]<Rp[i]) && (LIDAR->RangeMeasurements[i]<=Rn[i]))) {
Imin[i] = true;
}
}
return Imin;
}
polygon localworkspaceLIDAR2D(point RobotPosition, double RobotOrientation, double RobotRadius, LIDARClass* LIDAR) {
/**
* Function that returns the local workspace
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) RobotRadius: Robot radius
* 4) LIDAR: Current LIDAR object, assumed to be in the (-pi, pi) range
*
* Output:
* 1) LW: Local workspace polygon
*/
// Initialize vector of ranges
double epsilon = 0.000000001;
std::vector<double> R(LIDAR->RangeMeasurements.size(), LIDAR->Range);
polygon LW;
if (*std::min_element(LIDAR->RangeMeasurements.begin(), LIDAR->RangeMeasurements.end()) < epsilon) {
return LW;
} else {
// Modify range data defining the local workspace and the local footprint
std::vector<point> ListOfPointsFootprint(R.size());
for (size_t i = 0; i < R.size(); i++) {
R[i] = 0.5*(LIDAR->RangeMeasurements[i]+RobotRadius);
ListOfPointsFootprint[i] = point(R[i]*cos(LIDAR->Angle[i]+RobotOrientation), R[i]*sin(LIDAR->Angle[i]+RobotOrientation));
}
// Initialize the local workspace with the minimum square that respects the LIDAR's sensing range
std::vector<point> ListOfPoints = {point(-10,-10), point(10,-10), point(10,10), point(-10,10), point(-10,-10)};
LW = BoostPointToBoostPoly(ListOfPoints);
std::vector<bool> Imin = localminLIDAR2D(LIDAR);
for (size_t k = 0; k < Imin.size(); k++) {
if (Imin[k]) {
if (bg::area(LW) < 0.01) {
return LW;
} else {
// Local minimum parameters
double Ak = LIDAR->Angle[k]; // Angle
double Rk = R[k]; // Range
// Separating hyperplane parameters
point n(-cos(Ak+RobotOrientation), -sin(Ak+RobotOrientation)); // Hyperplane normal
point m(-Rk*n.get<0>(), -Rk*n.get<1>()); // A point on the separating hyperplane
// Update the local workspace by taking its intersection with the associated halfplane
LW = cvxpolyxhplane(LW, m, n);
}
} else {
continue;
}
}
// Local workspace footprint
polygon LocalFootprint = BoostPointToBoostPoly(ListOfPointsFootprint);
// Update local workspace
if (bg::is_valid(LW) && bg::is_valid(LocalFootprint)) {
multi_polygon intersection_output;
bg::intersection(LW, LocalFootprint, intersection_output);
polygon LW_out;
if (intersection_output.empty()) {
return LW_out;
} else {
std::vector<std::vector<double>> transform = {{1, 0, RobotPosition.get<0>()}, {0, 1, RobotPosition.get<1>()}, {0, 0, 1}};
bg::strategy::transform::matrix_transformer<double, 2, 2> transform_strategy(transform[0][0], transform[0][1], transform[0][2],
transform[1][0], transform[1][1], transform[1][2],
transform[2][0], transform[2][1], transform[2][2]);
bg::transform(intersection_output[0], LW_out, transform_strategy);
// Make local workspace convex
polygon LW_final;
bg::convex_hull(LW_out, LW_final);
return LW_final;
}
}
}
return LW;
}
polygon localfreespaceLIDAR2D(point RobotPosition, double RobotOrientation, double RobotRadius, LIDARClass* LIDAR) {
/**
* Function that returns the local workspace
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) RobotRadius: Robot radius
* 4) LIDAR: Current LIDAR object - assumed to be in the (-pi, pi) range
*
* Output:
* 1) LF: Local freespace polygon
*/
// Initialize vector of ranges
double epsilon = 0.000000001;
std::vector<double> R = LIDAR->RangeMeasurements;
polygon LF;
if (*std::min_element(LIDAR->RangeMeasurements.begin(), LIDAR->RangeMeasurements.end()) < epsilon) {
return LF;
} else {
// Modify range data defining the local workspace and the local footprint
std::vector<point> ListOfPointsFootprint(R.size());
for (size_t i = 0; i < R.size(); i++) {
R[i] = 0.5*(LIDAR->RangeMeasurements[i]-RobotRadius);
ListOfPointsFootprint[i] = point(R[i]*cos(LIDAR->Angle[i]+RobotOrientation), R[i]*sin(LIDAR->Angle[i]+RobotOrientation));
}
// Initialize the local workspace with the minimum square that respects the LIDAR's sensing range
std::vector<point> ListOfPoints = {point(-10.0,-10.0), point(10.0,-10.0), point(10.0,10.0), point(-10.0,10.0), point(-10.0,-10.0)};
LF = BoostPointToBoostPoly(ListOfPoints);
std::vector<bool> Imin = localminLIDAR2D(LIDAR);
for (size_t k = 0; k < Imin.size(); k++) {
if (Imin[k]) {
if (bg::area(LF) < 0.01) {
return LF;
} else {
// Local minimum parameters
double Ak = LIDAR->Angle[k]; // Angle
double Rk = R[k]; // Range
// Separating hyperplane parameters
point n(-cos(Ak+RobotOrientation), -sin(Ak+RobotOrientation)); // Hyperplane normal
point m(-Rk*n.get<0>(), -Rk*n.get<1>()); // A point on the separating hyperplane
// Update the local workspace by taking its intersection with the associated halfplane
LF = cvxpolyxhplane(LF, m, n);
}
} else {
continue;
}
}
// Local workspace footprint
polygon LocalFootprint = BoostPointToBoostPoly(ListOfPointsFootprint);
// Update local workspace
if (bg::is_valid(LF) && bg::is_valid(LocalFootprint)) {
multi_polygon intersection_output;
bg::intersection(LF, LocalFootprint, intersection_output);
polygon LF_out;
if (intersection_output.empty()) {
return LF_out;
} else {
std::vector<std::vector<double>> transform = {{1, 0, RobotPosition.get<0>()}, {0, 1, RobotPosition.get<1>()}, {0, 0, 1}};
bg::strategy::transform::matrix_transformer<double, 2, 2> transform_strategy(transform[0][0], transform[0][1], transform[0][2],
transform[1][0], transform[1][1], transform[1][2],
transform[2][0], transform[2][1], transform[2][2]);
bg::transform(intersection_output[0], LF_out, transform_strategy);
// Make local workspace convex
polygon LF_final;
bg::convex_hull(LF_out, LF_final);
return LF_final;
}
}
}
return LF;
}
line localfreespace_linearLIDAR2D(point RobotPosition, double RobotOrientation, polygon LF) {
/**
* Function that returns the linear local freespace as the intersection of the local freespace with the current heading line
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) LF: Local freespace
*
* Output:
* 1) LFL: Linear freespace
*/
// Initialize line
line LFL;
if (bg::area(LF) < 0.01) {
LFL.push_back(RobotPosition);
LFL.push_back(RobotPosition);
return LFL;
} else {
LFL.push_back(RobotPosition);
LFL.push_back(polyxray(LF, RobotPosition, point(cos(RobotOrientation), sin(RobotOrientation))));
return LFL;
}
}
line localfreespace_angularLIDAR2D(point RobotPosition, double RobotOrientation, polygon LF, point Goal) {
/**
* Function that returns the angular local freespace as the intersection of the local freespace with the line connecting the robot to the goal
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) LF: Local freespace
* 4) Goal: Designated goal
*
* Output:
* 1) LFA: Angular freespace
*/
// Initialize line
line LFA;
if (bg::area(LF) < 0.01) {
LFA.push_back(RobotPosition);
LFA.push_back(RobotPosition);
return LFA;
} else {
LFA.push_back(RobotPosition);
LFA.push_back(Goal);
std::deque<line> LFA_deque;
line LFA_final;
bg::intersection(LFA, LF, LFA_deque);
if (LFA_deque.size() > 0) {
LFA_final = LFA_deque[0];
}
return LFA_final;
}
}
point localgoalLIDAR2D(polygon LF, point Goal) {
/**
* Function that computes the local goal as the projection of the global goal on the local freespace
*
* Input:
* 1) LF: Local freespace
* 2) Goal: Designated goal
*
* Output:
* 1) LG: Local goal
*/
// Compute local goal - the closest point of local free space to the global goal
if (bg::area(LF) < 0.01) {
return Goal;
} else {
if (bg::within(Goal, LF)) {
return Goal;
} else {
ProjectionResultStruct projection = polydist(LF, Goal);
return projection.projected_point;
}
}
}
point localgoal_linearLIDAR2D(point RobotPosition, double RobotOrientation, polygon LF, point Goal) {
/**
* Function that computes the linear local goal as the projection of the global goal on the linear local freespace
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) LF: Local freespace
* 4) Goal: Global goal
*
* Output:
* 1) LG: Local linear goal
*/
// Compute linear local free space
line LFL = localfreespace_linearLIDAR2D(RobotPosition, RobotOrientation, LF);
// Compute local goal for unicycle
if (bg::is_empty(LFL)) {
return RobotPosition;
} else {
ProjectionResultStruct projection = linedist(LFL, Goal);
return projection.projected_point;
}
}
point localgoal_angularLIDAR2D(point RobotPosition, double RobotOrientation, polygon LF, point Goal) {
/**
* Function that computes the linear local goal as the projection of the global goal on the linear local freespace
*
* Input:
* 1) RobotPosition: Robot position
* 2) RobotOrientation: Robot orientation
* 3) LF: Local freespace
* 4) Goal: Global goal
*
* Output:
* 1) LG: Local angular goal
*/
// Compute angular local free space
line LFA = localfreespace_angularLIDAR2D(RobotPosition, RobotOrientation, LF, Goal);
// Compute local goal for unicycle
if (bg::is_empty(LFA)) {
return Goal;
} else {
ProjectionResultStruct projection = linedist(LFA, Goal);
return projection.projected_point;
}
}
void diffeoTreeTriangulation(std::vector<std::vector<double>> PolygonVertices, DiffeoParamsClass DiffeoParams, std::vector<TriangleClass> *tree) {
/**
* Function that calculates the triangulation tree of a polygon and augments it with properties used in semantic navigation (based on the ear clipping method)
*
* Input:
* 1) PolygonVertices: Vertex Coordinates of input polygon (start and end vertices must be the same)
* 2) DiffeoParams: Options for the diffeomorphism construction
* 3) tree: Stack of triangles with all the desired properties
*
*/
// Create a dummy origin
point origin(0.0, 0.0);
// Unpack diffeomorphism parameters
double varepsilon = DiffeoParams.get_varepsilon();
std::vector<std::vector<double>> workspace = DiffeoParams.get_workspace();
// Construct a polygon based on the input vertices - TODO: Check that the polygon is closed
polygon PolygonIn = BoostPointToBoostPoly(StdToBoostPoint(PolygonVertices));
// Construct a line and a polygon based on the workspace
line workspaceLine = BoostPointToBoostLine(StdToBoostPoint(workspace));
polygon workspacePolygon = BoostPointToBoostPoly(StdToBoostPoint(workspace));
// Check if the polygon intersects the workspace boundary
if (bg::intersects(PolygonIn, workspaceLine)) {
// Compute the intersection with the workspace
multi_polygon polygon_to_use;
bg::intersection(PolygonIn, workspacePolygon, polygon_to_use);
// Find the vertices of the polygon
std::vector<std::vector<double>> PolygonVertexList = BoostPointToStd(BoostPolyToBoostPoint(polygon_to_use[0]));
// Compute the triangulation tree of the polygon with its dual (adjacency) graph
polytriangulation(PolygonVertexList, workspace, true, tree);
// Find the center and the adjacency edge to the boundary
std::vector<point> last_triangle_vertices = tree->back().get_vertices();
std::vector<double> dist_vector(3, 0.0);
for (size_t i = 0; i < 3; i++) {
dist_vector[i] = bg::distance(last_triangle_vertices[i], workspaceLine);
}
size_t min_dist_element = std::distance(dist_vector.begin(), std::min_element(dist_vector.begin(), dist_vector.end()));
point median_point;
switch(min_dist_element) {
case 0:
if(dist_vector[1] <= dist_vector[2]) {
tree->back().set_vertices({last_triangle_vertices[0], last_triangle_vertices[1], last_triangle_vertices[2]});
tree->back().set_adj_edge({last_triangle_vertices[0], last_triangle_vertices[1]});
median_point.set<0>(0.5*(last_triangle_vertices[0].get<0>()+last_triangle_vertices[1].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[0].get<1>()+last_triangle_vertices[1].get<1>()));
} else {
tree->back().set_vertices({last_triangle_vertices[2], last_triangle_vertices[0], last_triangle_vertices[1]});
tree->back().set_adj_edge({last_triangle_vertices[2], last_triangle_vertices[0]});
median_point.set<0>(0.5*(last_triangle_vertices[2].get<0>()+last_triangle_vertices[0].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[2].get<1>()+last_triangle_vertices[0].get<1>()));
}
break;
case 1:
if(dist_vector[0] <= dist_vector[2]) {
tree->back().set_vertices({last_triangle_vertices[0], last_triangle_vertices[1], last_triangle_vertices[2]});
tree->back().set_adj_edge({last_triangle_vertices[0], last_triangle_vertices[1]});
median_point.set<0>(0.5*(last_triangle_vertices[0].get<0>()+last_triangle_vertices[1].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[0].get<1>()+last_triangle_vertices[1].get<1>()));
} else {
tree->back().set_vertices({last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0]});
tree->back().set_adj_edge({last_triangle_vertices[1], last_triangle_vertices[2]});
median_point.set<0>(0.5*(last_triangle_vertices[1].get<0>()+last_triangle_vertices[2].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[1].get<1>()+last_triangle_vertices[2].get<1>()));
}
break;
case 2:
if(dist_vector[0] <= dist_vector[1]) {
tree->back().set_vertices({last_triangle_vertices[2], last_triangle_vertices[0], last_triangle_vertices[1]});
tree->back().set_adj_edge({last_triangle_vertices[2], last_triangle_vertices[0]});
median_point.set<0>(0.5*(last_triangle_vertices[2].get<0>()+last_triangle_vertices[0].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[2].get<1>()+last_triangle_vertices[0].get<1>()));
} else {
tree->back().set_vertices({last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0]});
tree->back().set_adj_edge({last_triangle_vertices[1], last_triangle_vertices[2]});
median_point.set<0>(0.5*(last_triangle_vertices[1].get<0>()+last_triangle_vertices[2].get<0>()));
median_point.set<1>(0.5*(last_triangle_vertices[1].get<1>()+last_triangle_vertices[2].get<1>()));
}
break;
}
last_triangle_vertices = tree->back().get_vertices();
point median_ray(median_point.get<0>()-last_triangle_vertices[2].get<0>(), median_point.get<1>()-last_triangle_vertices[2].get<1>());
median_ray.set<0>(median_ray.get<0>()/bg::distance(median_ray,origin));
median_ray.set<1>(median_ray.get<1>()/bg::distance(median_ray,origin));
point last_triangle_center(median_point.get<0>()+1.0*median_ray.get<0>(), median_point.get<1>()+1.0*median_ray.get<1>());
tree->back().set_center(last_triangle_center);
// Compute the tangent and normal vectors of the root triangle
std::vector<point> r_t_vector = {point((last_triangle_vertices[1].get<0>()-last_triangle_vertices[0].get<0>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[1]), (last_triangle_vertices[1].get<1>()-last_triangle_vertices[0].get<1>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[1])), point((last_triangle_vertices[2].get<0>()-last_triangle_vertices[1].get<0>())/bg::distance(last_triangle_vertices[1],last_triangle_vertices[2]), (last_triangle_vertices[2].get<1>()-last_triangle_vertices[1].get<1>())/bg::distance(last_triangle_vertices[1],last_triangle_vertices[2])), point((last_triangle_vertices[0].get<0>()-last_triangle_vertices[2].get<0>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[2]), (last_triangle_vertices[0].get<1>()-last_triangle_vertices[2].get<1>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[2]))};
std::vector<point> r_n_vector = {point(-r_t_vector[0].get<1>(), r_t_vector[0].get<0>()), point(-r_t_vector[1].get<1>(), r_t_vector[1].get<0>()), point(-r_t_vector[2].get<1>(), r_t_vector[2].get<0>())};
tree->back().set_r_t(r_t_vector);
tree->back().set_r_n(r_n_vector);
// Find the remaining tangents and normals from vertices 0 and 1 to the center
std::vector<point> r_center_t_vector = {point((last_triangle_center.get<0>()-last_triangle_vertices[0].get<0>())/bg::distance(last_triangle_vertices[0],last_triangle_center), (last_triangle_center.get<1>()-last_triangle_vertices[0].get<1>())/bg::distance(last_triangle_vertices[0],last_triangle_center)), point((last_triangle_vertices[1].get<0>()-last_triangle_center.get<0>())/bg::distance(last_triangle_vertices[1],last_triangle_center), (last_triangle_vertices[1].get<1>()-last_triangle_center.get<1>())/bg::distance(last_triangle_vertices[1],last_triangle_center))};
std::vector<point> r_center_n_vector = {point(-r_center_t_vector[0].get<1>(), r_center_t_vector[0].get<0>()), point(-r_center_t_vector[1].get<1>(), r_center_t_vector[1].get<0>())};
tree->back().set_r_center_t(r_center_t_vector);
tree->back().set_r_center_n(r_center_n_vector);
// Compute the dilated polygon and truncate it by the rays emanating from the center
bg::strategy::buffer::distance_symmetric<double> distance_strategy(varepsilon);
polygon last_triangle_polygon = BoostPointToBoostPoly({last_triangle_vertices[0], last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0]});
multi_polygon last_triangle_multipolygon_dilated;
bg::buffer(last_triangle_polygon, last_triangle_multipolygon_dilated, distance_strategy, side_strategy, join_strategy, end_strategy, circle_strategy);
polygon last_triangle_polygon_dilated = last_triangle_multipolygon_dilated.front();
polygon intersect_1 = cvxpolyxhplane(last_triangle_polygon_dilated, last_triangle_center, tree->back().get_r_center_n().front());
polygon intersect_2 = cvxpolyxhplane(intersect_1, last_triangle_center, tree->back().get_r_center_n().back());
// Compute the intersection with the workspace
multi_polygon output_1;
multi_polygon output_2;
polygon final_polygon;
bg::intersection(intersect_2, workspacePolygon, output_1);
bg::union_(output_1[0], BoostPointToBoostPoly({last_triangle_center, last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0], last_triangle_center}), output_2);
bg::simplify(output_2[0], final_polygon, 0.02);
std::vector<point> last_triangle_vertices_tilde = BoostPolyToBoostPoint(final_polygon);
last_triangle_vertices_tilde.pop_back();
tree->back().set_vertices_tilde(last_triangle_vertices_tilde);
// Find the tangent and normal vectors for the generated polygonal collar
std::vector<point> r_tilde_t_vector, r_tilde_n_vector;
for (size_t i = 0; i < last_triangle_vertices_tilde.size(); i++) {
size_t j = (i+1)%(last_triangle_vertices_tilde.size());
double dist_ij = bg::distance(last_triangle_vertices_tilde[i],last_triangle_vertices_tilde[j]);
r_tilde_t_vector.push_back(point((last_triangle_vertices_tilde[j].get<0>()-last_triangle_vertices_tilde[i].get<0>())/dist_ij, (last_triangle_vertices_tilde[j].get<1>()-last_triangle_vertices_tilde[i].get<1>())/dist_ij));
r_tilde_n_vector.push_back(point(-(last_triangle_vertices_tilde[j].get<1>()-last_triangle_vertices_tilde[i].get<1>())/dist_ij, (last_triangle_vertices_tilde[j].get<0>()-last_triangle_vertices_tilde[i].get<0>())/dist_ij));
}
tree->back().set_r_tilde_t(r_tilde_t_vector);
tree->back().set_r_tilde_n(r_tilde_n_vector);
// Add a dummy radius
tree->back().set_radius(0.0);
} else {
// Compute the triangulation tree of the polygon with its dual (adjacency) graph
polytriangulation(PolygonVertices, workspace, false, tree);
// Find the center and radius of the root
std::vector<point> last_triangle_vertices = tree->back().get_vertices();
tree->back().set_center(point((last_triangle_vertices[0].get<0>()+last_triangle_vertices[1].get<0>()+last_triangle_vertices[2].get<0>())/3.0, (last_triangle_vertices[0].get<1>()+last_triangle_vertices[1].get<1>()+last_triangle_vertices[2].get<1>())/3.0));
tree->back().set_radius(0.8*bg::distance(tree->back().get_center(), BoostPointToBoostLine({last_triangle_vertices[0], last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0]})));
// Compute the tangent and normal vectors of the root triangle
std::vector<point> r_t_vector = {point((last_triangle_vertices[1].get<0>()-last_triangle_vertices[0].get<0>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[1]), (last_triangle_vertices[1].get<1>()-last_triangle_vertices[0].get<1>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[1])), point((last_triangle_vertices[2].get<0>()-last_triangle_vertices[1].get<0>())/bg::distance(last_triangle_vertices[1],last_triangle_vertices[2]), (last_triangle_vertices[2].get<1>()-last_triangle_vertices[1].get<1>())/bg::distance(last_triangle_vertices[1],last_triangle_vertices[2])), point((last_triangle_vertices[0].get<0>()-last_triangle_vertices[2].get<0>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[2]), (last_triangle_vertices[0].get<1>()-last_triangle_vertices[2].get<1>())/bg::distance(last_triangle_vertices[0],last_triangle_vertices[2]))};
std::vector<point> r_n_vector = {point(-r_t_vector[0].get<1>(), r_t_vector[0].get<0>()), point(-r_t_vector[1].get<1>(), r_t_vector[1].get<0>()), point(-r_t_vector[2].get<1>(), r_t_vector[2].get<0>())};
tree->back().set_r_t(r_t_vector);
tree->back().set_r_n(r_n_vector);
// Find the polygonal color for the root by dilating the triangle by varepsilon
bg::strategy::buffer::distance_symmetric<double> distance_strategy(varepsilon);
polygon last_triangle_polygon = BoostPointToBoostPoly({last_triangle_vertices[0], last_triangle_vertices[1], last_triangle_vertices[2], last_triangle_vertices[0]});
multi_polygon last_triangle_multipolygon_dilated;
bg::buffer(last_triangle_polygon, last_triangle_multipolygon_dilated, distance_strategy, side_strategy, join_strategy, end_strategy, circle_strategy);
polygon last_triangle_polygon_dilated = last_triangle_multipolygon_dilated.front();
// Compute the intersection with the workspace
multi_polygon output_1;
polygon final_polygon;
bg::intersection(last_triangle_polygon_dilated, workspacePolygon, output_1);
bg::simplify(output_1[0], final_polygon, 0.02);
std::vector<point> last_triangle_vertices_tilde = BoostPolyToBoostPoint(final_polygon);
last_triangle_vertices_tilde.pop_back();
tree->back().set_vertices_tilde(last_triangle_vertices_tilde);
// Find the tangent and normal vectors for the generated polygonal collar
std::vector<point> r_tilde_t_vector, r_tilde_n_vector;
for (size_t i = 0; i < last_triangle_vertices_tilde.size(); i++) {
size_t j = (i+1)%(last_triangle_vertices_tilde.size());
double dist_ij = bg::distance(last_triangle_vertices_tilde[i],last_triangle_vertices_tilde[j]);
r_tilde_t_vector.push_back(point((last_triangle_vertices_tilde[j].get<0>()-last_triangle_vertices_tilde[i].get<0>())/dist_ij, (last_triangle_vertices_tilde[j].get<1>()-last_triangle_vertices_tilde[i].get<1>())/dist_ij));
r_tilde_n_vector.push_back(point(-(last_triangle_vertices_tilde[j].get<1>()-last_triangle_vertices_tilde[i].get<1>())/dist_ij, (last_triangle_vertices_tilde[j].get<0>()-last_triangle_vertices_tilde[i].get<0>())/dist_ij));
}
tree->back().set_r_tilde_t(r_tilde_t_vector);
tree->back().set_r_tilde_n(r_tilde_n_vector);
}
// Identify all the children properties
for (size_t i = 0; i < tree->size()-1; i++) {
// Compute the tangent and normal vectors of the child hyperplanes
// r0 is always the shared edge between the parent and the child, r1 and r2 the rest in CCW order
std::vector<point> triangle_vertices = (*tree)[i].get_vertices();
std::vector<point> r_t_vector = {point((triangle_vertices[1].get<0>()-triangle_vertices[0].get<0>())/bg::distance(triangle_vertices[0],triangle_vertices[1]), (triangle_vertices[1].get<1>()-triangle_vertices[0].get<1>())/bg::distance(triangle_vertices[0],triangle_vertices[1])), point((triangle_vertices[2].get<0>()-triangle_vertices[1].get<0>())/bg::distance(triangle_vertices[1],triangle_vertices[2]), (triangle_vertices[2].get<1>()-triangle_vertices[1].get<1>())/bg::distance(triangle_vertices[1],triangle_vertices[2])), point((triangle_vertices[0].get<0>()-triangle_vertices[2].get<0>())/bg::distance(triangle_vertices[0],triangle_vertices[2]), (triangle_vertices[0].get<1>()-triangle_vertices[2].get<1>())/bg::distance(triangle_vertices[0],triangle_vertices[2]))};
std::vector<point> r_n_vector = {point(-r_t_vector[0].get<1>(), r_t_vector[0].get<0>()), point(-r_t_vector[1].get<1>(), r_t_vector[1].get<0>()), point(-r_t_vector[2].get<1>(), r_t_vector[2].get<0>())};
(*tree)[i].set_r_t(r_t_vector);
(*tree)[i].set_r_n(r_n_vector);
// Find the median from the 3rd point to the shared edge and from that compute the center for the purging transformation
std::vector<point> triangle_adj_edge = (*tree)[i].get_adj_edge();
point median_point;
median_point.set<0>(0.5*(triangle_adj_edge[0].get<0>()+triangle_adj_edge[1].get<0>()));
median_point.set<1>(0.5*(triangle_adj_edge[0].get<1>()+triangle_adj_edge[1].get<1>()));
point median_ray(median_point.get<0>()-triangle_vertices[2].get<0>(), median_point.get<1>()-triangle_vertices[2].get<1>());
median_ray.set<0>(median_ray.get<0>()/bg::distance(median_ray,origin));
median_ray.set<1>(median_ray.get<1>()/bg::distance(median_ray,origin));
std::vector<point> predecessor_triangle_vertices = (*tree)[(*tree)[i].get_predecessor()].get_vertices();
point intersection_point = polyxray(BoostPointToBoostPoly({predecessor_triangle_vertices[0], predecessor_triangle_vertices[1], predecessor_triangle_vertices[2], predecessor_triangle_vertices[0]}), median_point, median_ray);
point triangle_center(0.2*median_point.get<0>()+0.8*intersection_point.get<0>(), 0.2*median_point.get<1>()+0.8*intersection_point.get<1>());
(*tree)[i].set_center(triangle_center);
// Find the remaining tangents and normals from vertices 0 and 1 to the center
std::vector<point> r_center_t_vector = {point((triangle_center.get<0>()-triangle_vertices[0].get<0>())/bg::distance(triangle_vertices[0],triangle_center), (triangle_center.get<1>()-triangle_vertices[0].get<1>())/bg::distance(triangle_vertices[0],triangle_center)), point((triangle_vertices[1].get<0>()-triangle_center.get<0>())/bg::distance(triangle_vertices[1],triangle_center), (triangle_vertices[1].get<1>()-triangle_center.get<1>())/bg::distance(triangle_vertices[1],triangle_center))};
std::vector<point> r_center_n_vector = {point(-r_center_t_vector[0].get<1>(), r_center_t_vector[0].get<0>()), point(-r_center_t_vector[1].get<1>(), r_center_t_vector[1].get<0>())};
(*tree)[i].set_r_center_t(r_center_t_vector);
(*tree)[i].set_r_center_n(r_center_n_vector);
// Compute the dilated polygon and truncate it by the rays emanating from the center
bg::strategy::buffer::distance_symmetric<double> distance_strategy(varepsilon);
polygon triangle_polygon = BoostPointToBoostPoly({triangle_vertices[0], triangle_vertices[1], triangle_vertices[2], triangle_vertices[0]});
multi_polygon triangle_multipolygon_dilated;
bg::buffer(triangle_polygon, triangle_multipolygon_dilated, distance_strategy, side_strategy, join_strategy, end_strategy, circle_strategy);
polygon triangle_polygon_dilated = triangle_multipolygon_dilated.front();
polygon intersect_1 = cvxpolyxhplane(triangle_polygon_dilated, triangle_center, (*tree)[i].get_r_center_n().front());
polygon intersect_2 = cvxpolyxhplane(intersect_1, triangle_center, (*tree)[i].get_r_center_n().back());
polygon candidate_polygon = intersect_2;
// Check for collisions with all the triangles that will succeed i in the diffeomorphism construction except for its parent
for (size_t j = i+1; j < tree->size(); j++) {
if (j == (*tree)[i].get_predecessor()) {
continue;
} else {
std::vector<point> triangle_to_test_vertices = (*tree)[j].get_vertices();
polygon triangle_to_test = BoostPointToBoostPoly({triangle_to_test_vertices[0], triangle_to_test_vertices[1], triangle_to_test_vertices[2], triangle_to_test_vertices[0]});
multi_polygon difference_output;
bg::difference(candidate_polygon, triangle_to_test, difference_output);
// If the difference operation created a multipolygon, keep only the polygon that contains the barycenter of the extended triangle
point point_to_consider((triangle_vertices[0].get<0>()+triangle_vertices[1].get<0>()+triangle_center.get<0>())/3.0, (triangle_vertices[0].get<1>()+triangle_vertices[1].get<1>()+triangle_center.get<1>())/3.0);
BOOST_FOREACH(polygon const& difference_component, difference_output) {
if (bg::within(point_to_consider, difference_component)) {
candidate_polygon = difference_component;
break;
}
}
}
}
// Extract final vertices
polygon candidate_polygon_simplified = candidate_polygon;
bg::simplify(candidate_polygon, candidate_polygon_simplified, 0.02);
std::vector<std::vector<double>> candidate_polygon_vertices = BoostPointToStd(BoostPolyToBoostPoint(candidate_polygon_simplified));
candidate_polygon_vertices.pop_back();
// Decompose the polygon into its convex pieces and find the piece that includes the barycenter of the extended triangle
CGAL_Polygon_2 cgal_polygon;
CGAL_Polygon_list partition_polys;
CGAL_Traits partition_traits;
CGAL::set_pretty_mode(std::cout);
std::vector<point> final_polygon_vertices;
for (size_t k = 0; k < candidate_polygon_vertices.size(); k++) {
cgal_polygon.push_back(CGAL_Point_2(candidate_polygon_vertices[k][0], candidate_polygon_vertices[k][1]));
}
if (cgal_polygon.is_simple()) {
// std::cout << cgal_polygon << std::endl;
CGAL::greene_approx_convex_partition_2(cgal_polygon.vertices_begin(),
cgal_polygon.vertices_end(),
std::back_inserter(partition_polys),
partition_traits);
assert(CGAL::convex_partition_is_valid_2(cgal_polygon.vertices_begin(),
cgal_polygon.vertices_end(),
partition_polys.begin(),
partition_polys.end(),
partition_traits));
CGAL_Point_2 cgal_point_to_consider((triangle_vertices[0].get<0>()+triangle_vertices[1].get<0>()+triangle_center.get<0>())/3.0, (triangle_vertices[0].get<1>()+triangle_vertices[1].get<1>()+triangle_center.get<1>())/3.0);
for (size_t k = 0; k < partition_polys.size(); k++) {
auto it = std::next(partition_polys.begin(), k);
CGAL_Polygon_2 polygon_to_consider = *it;
final_polygon_vertices = {};
for (size_t l = 0; l < polygon_to_consider.size(); l++) {
final_polygon_vertices.push_back(point(polygon_to_consider.vertex(l).x(), polygon_to_consider.vertex(l).y()));
}
final_polygon_vertices.push_back(final_polygon_vertices[0]);
if (bg::within(point((triangle_vertices[0].get<0>()+triangle_vertices[1].get<0>()+triangle_center.get<0>())/3.0, (triangle_vertices[0].get<1>()+triangle_vertices[1].get<1>()+triangle_center.get<1>())/3.0), BoostPointToBoostPoly(final_polygon_vertices))) {
break;
}
}
} else {
final_polygon_vertices = BoostPolyToBoostPoint(intersect_2);