-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathBFMT_8cpp_source.html
More file actions
1140 lines (1138 loc) · 215 KB
/
BFMT_8cpp_source.html
File metadata and controls
1140 lines (1138 loc) · 215 KB
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
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="utf-8">
<meta name="viewport" content="width=device-width, initial-scale=1, shrink-to-fit=no">
<meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki">
<meta name="generator" content="Doxygen 1.8.17"/>
<title>ompl/geometric/planners/fmt/src/BFMT.cpp Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script src="jquery.js"></script>
<script src="dynsections.js"></script>
<link href="search/search.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="search/searchdata.js"></script>
<script type="text/javascript" src="search/search.js"></script>
<script type="text/javascript">
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
$(document).ready(function() { init_search(); });
/* @license-end */
</script>
<script type="text/x-mathjax-config">
MathJax.Hub.Config({
extensions: ["tex2jax.js", "TeX/AMSmath.js", "TeX/AMSsymbols.js"],
jax: ["input/TeX","output/HTML-CSS"],
});
</script>
<script type="text/javascript" async="async" src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/MathJax.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
<link rel="stylesheet" href="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/css/bootstrap.min.css" integrity="sha384-ggOyR0iXCbMQv3Xipma34MD+dH/1fQ784/j6cY/iJTQUOhcWr7x9JvoRxT2MZw1T" crossorigin="anonymous">
<link href="ompl.css" rel="stylesheet">
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<nav class="navbar navbar-expand-md fixed-top navbar-dark">
<a class="navbar-brand" href="./index.html">OMPL</a>
<button class="navbar-toggler" type="button" data-toggle="collapse" data-target="#navbar">
<span class="navbar-toggler-icon"></span>
</button>
<div class="collapse navbar-collapse" id="navbar">
<ul class="navbar-nav mr-auto">
<li class="nav-item"><a class="nav-link" href="download.html">Download</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="docDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Documentation</a>
<div class="dropdown-menu" aria-labelledby="docDropdown">
<a class="dropdown-item" href="https://ompl.kavrakilab.org/OMPL_Primer.pdf">Primer</a>
<a class="dropdown-item" href="installation.html">Installation</a>
<a class="dropdown-item" href="tutorials.html">Tutorials</a>
<a class="dropdown-item" href="group__demos.html">Demos</a>
<a class="dropdown-item omplapp" href="gui.html">OMPL.app GUI</a>
<a class="dropdown-item omplapp" href="webapp.html">OMPL web app</a>
<a class="dropdown-item" href="python.html">Python Bindings</a>
<a class="dropdown-item" href="planners.html">Available Planners</a>
<a class="dropdown-item" href="plannerTerminationConditions.html">Planner Termination Conditions</a>
<a class="dropdown-item" href="benchmark.html">Benchmarking Planners</a>
<a class="dropdown-item" href="spaces.html">Available State Spaces</a>
<a class="dropdown-item" href="optimalPlanning.html">Optimal Planning</a>
<a class="dropdown-item" href="constrainedPlanning.html">Constrained Planning</a>
<a class="dropdown-item" href="multiLevelPlanning.html">Multilevel Planning</a>
<a class="dropdown-item" href="FAQ.html">FAQ</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">External links</div>
<a class="dropdown-item" href="http://moveit.ros.org">MoveIt</a>
<a class="dropdown-item" href="http://plannerarena.org">Planner Arena</a>
<a class="dropdown-item" href="https://moveit.ros.org//moveit!/ros/2013/05/07/icra-motion-planning-tutorial.html">ICRA 2013 Tutorial</a>
<a class="dropdown-item" href="http://kavrakilab.org/iros2011/">IROS 2011 Tutorial</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="gallery.html">Gallery</a></li>
<li class="nav-item"><a class="nav-link" href="integration.html">OMPL Integrations</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="codeDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Code</a>
<div class="dropdown-menu" aria-labelledby="codeDropdown">
<a class="dropdown-item" href="api_overview.html">API Overview</a>
<a class="dropdown-item" href="annotated.html">Classes</a>
<a class="dropdown-item" href="files.html">Files</a>
<a class="dropdown-item" href="styleGuide.html">Style Guide</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">Repositories</div>
<a class="dropdown-item" href="https://github.com/ompl/ompl">ompl on GitHub</a>
<a class="dropdown-item" href="https://github.com/ompl/omplapp">omplapp on GitHub</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">Continuous Integration</div>
<a class="dropdown-item" href="https://travis-ci.org/ompl/ompl">ompl on Travis CI (Linux/macOS)</a>
<a class="dropdown-item" href="https://travis-ci.org/ompl/omplapp">omplapp on Travis CI (Linux/macOS)</a>
<a class="dropdown-item" href="https://ci.appveyor.com/project/mamoll/ompl">ompl on AppVeyor CI (Windows)</a>
<a class="dropdown-item" href="https://ci.appveyor.com/project/mamoll/omplapp">omplapp on AppVeyor CI (Windows)</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://github.com/ompl/ompl/issues">Issues</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="communityDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Community</a>
<div class="dropdown-menu" aria-labelledby="communityDropdown">
<a class="dropdown-item" href="support.html">Get Support</a>
<a class="dropdown-item" href="developers.html">Developers/Contributors</a>
<a class="dropdown-item" href="contrib.html">Submit a Contribution</a>
<a class="dropdown-item" href="education.html">Education</a>
</div>
</li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="aboutDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">About</a>
<div class="dropdown-menu" aria-labelledby="aboutDropdown">
<a class="dropdown-item" href="license.html">License</a>
<a class="dropdown-item" href="citations.html">Citations</a>
<a class="dropdown-item" href="acknowledgements.html">Acknowledgments</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://ompl.kavrakilab.org/blog.html">Blog</a></li>
</ul>
<div id="MSearchBox" class="MSearchBoxInactive">
<span class="left">
<img id="MSearchSelect" src="search/mag_sel.png"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
alt=""/>
<input type="text" id="MSearchField" value="Search" accesskey="S"
onfocus="searchBox.OnSearchFieldFocus(true)"
onblur="searchBox.OnSearchFieldFocus(false)"
onkeyup="searchBox.OnSearchFieldChange(event)"/>
</span><span class="right">
<a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
</span>
</div>
</div>
</nav>
<div class="container" role="main">
<div>
<!-- Generated by Doxygen 1.8.17 -->
<script type="text/javascript">
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
var searchBox = new SearchBox("searchBox", "search",false,'Search');
/* @license-end */
</script>
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
onkeydown="return searchBox.OnSearchSelectKey(event)">
</div>
<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="javascript:void(0)" frameborder="0"
name="MSearchResults" id="MSearchResults">
</iframe>
</div>
<div id="nav-path" class="navpath">
<ul>
<li class="navelem"><a class="el" href="dir_efdc19d105c21b1223d5f8dc524071be.html">ompl</a></li><li class="navelem"><a class="el" href="dir_1f57d97647ebda1e28cc730ac7313960.html">geometric</a></li><li class="navelem"><a class="el" href="dir_955a6a93aceef09599971796437d173a.html">planners</a></li><li class="navelem"><a class="el" href="dir_8a71c49e79ed8a582fb23771190907f1.html">fmt</a></li><li class="navelem"><a class="el" href="dir_d09bdf1a5c0b5184e6bb70b844cad66a.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">BFMT.cpp</div> </div>
</div><!--header-->
<div class="contents">
<div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span>  </div>
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="preprocessor">#include <boost/math/constants/constants.hpp></span></div>
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="preprocessor">#include <boost/math/distributions/binomial.hpp></span></div>
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span> <span class="preprocessor">#include <ompl/datastructures/BinaryHeap.h></span></div>
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> <span class="preprocessor">#include <ompl/tools/config/SelfConfig.h></span></div>
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span>  </div>
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="preprocessor">#include <ompl/datastructures/NearestNeighborsGNAT.h></span></div>
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span> <span class="preprocessor">#include <ompl/base/objectives/PathLengthOptimizationObjective.h></span></div>
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="preprocessor">#include <ompl/geometric/planners/fmt/BFMT.h></span></div>
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span>  </div>
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span> <span class="preprocessor">#include <fstream></span></div>
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="preprocessor">#include <ompl/base/spaces/RealVectorStateSpace.h></span></div>
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span>  </div>
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span> <span class="keyword">namespace </span><a class="code" href="namespaceompl.html">ompl</a></div>
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> {</div>
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span>  <span class="keyword">namespace </span>geometric</div>
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span>  {</div>
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span>  BFMT::BFMT(<span class="keyword">const</span> base::SpaceInformationPtr &si)</div>
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span>  : base::Planner(si, <span class="stringliteral">"BFMT"</span>)</div>
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span>  , freeSpaceVolume_(si_->getStateSpace()->getMeasure()) <span class="comment">// An upper bound on the free space volume is the</span></div>
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span>  <span class="comment">// total space volume; the free fraction is estimated</span></div>
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span>  <span class="comment">// in sampleFree</span></div>
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span>  {</div>
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.<a class="code" href="structompl_1_1base_1_1PlannerSpecs.html#ae2facc9260851b161577e36f5a4baefc">approximateSolutions</a> = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.<a class="code" href="structompl_1_1base_1_1PlannerSpecs.html#abe3ce1c340ba64c14644b0cace72907d">directed</a> = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span>  </div>
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span>  ompl::base::Planner::declareParam<unsigned int>(<span class="stringliteral">"num_samples"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a2419910ad98bb4bda23c2d549bd78aba">BFMT::setNumSamples</a>,</div>
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span>  &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ad8de03ea172cdc0377fae51d999edddc">BFMT::getNumSamples</a>, <span class="stringliteral">"10:10:1000000"</span>);</div>
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span>  ompl::base::Planner::declareParam<double>(<span class="stringliteral">"radius_multiplier"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#aea88fb1f6cd2dfb797557650c529fd65">BFMT::setRadiusMultiplier</a>,</div>
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span>  &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ae733d11654b2798ff4c1c89b7606f328">BFMT::getRadiusMultiplier</a>, <span class="stringliteral">"0.1:0.05:50."</span>);</div>
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"nearest_k"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#aee0ba4eabbfa73b3b74dbe001d8a1ce1">BFMT::setNearestK</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#afba43fda18541222dcd1851a5a7e3fde">BFMT::getNearestK</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"balanced"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a22c72868883fd9068a775473cc0793fd">BFMT::setExploration</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a817c266d5b1e8608301fcfe292b980ea">BFMT::getExploration</a>,</div>
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span>  <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"optimality"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a43a9b9542991c51567493f9a0767bc6a">BFMT::setTermination</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#abc03f1fc6372a7918ce8c0ac417b3f49">BFMT::getTermination</a>,</div>
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span>  <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"heuristics"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ae16d84f26ee1266de3f0689f0a0b7b64">BFMT::setHeuristics</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a5f24c8ceddbbc32fe8fd35d72cc79ba5">BFMT::getHeuristics</a>,</div>
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span>  <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"cache_cc"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a6d8c5ac49f2df6cbd0f8b276fdf0f138">BFMT::setCacheCC</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#a3a83596fb9d53fb86e81301966665683">BFMT::getCacheCC</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span>  ompl::base::Planner::declareParam<bool>(<span class="stringliteral">"extended_fmt"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ad3de0122ec209405dc4e973f85227273">BFMT::setExtendedFMT</a>, &<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ab2a06aae4282f6f3d3db6b71414bb9a5">BFMT::getExtendedFMT</a>,</div>
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span>  <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span>  }</div>
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span>  </div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span>  ompl::geometric::BFMT::~BFMT()</div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  {</div>
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a78b1fd3cfca7f4c32f2d3bf3a1fa5172">freeMemory</a>();</div>
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span>  }</div>
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span>  </div>
<div class="line"><a name="l00048"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a15a9b1b50f8747a53f8ea2e3ebd717b5"> 48</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a15a9b1b50f8747a53f8ea2e3ebd717b5">BFMT::setup</a>()</div>
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span>  {</div>
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>)</div>
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span>  {</div>
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  <span class="comment">/* Setup the optimization objective. If no optimization objective was</span></div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span> <span class="comment"> specified, then default to optimizing path length as computed by the</span></div>
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span> <span class="comment"> distance() function in the state space */</span></div>
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->hasOptimizationObjective())</div>
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a> = <a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->getOptimizationObjective();</div>
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span>  {</div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: No optimization objective specified. Defaulting to optimizing path length."</span>,</div>
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a> = std::make_shared<base::PathLengthOptimizationObjective>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>);</div>
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  <span class="comment">// Store the new objective in the problem def'n</span></div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->setOptimizationObjective(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>);</div>
<div class="line"><a name="l00064"></a><span class="lineno"> 64</span>  }</div>
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[0].<a class="code" href="classompl_1_1BinaryHeap.html#a99e2aec266c1746cf0f16aa763d00d7f">getComparisonOperator</a>().opt_ = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>.get();</div>
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[0].<a class="code" href="classompl_1_1BinaryHeap.html#a99e2aec266c1746cf0f16aa763d00d7f">getComparisonOperator</a>().heuristics_ = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a46469aa4f63eb64b41cc3fca8dc6d503">heuristics_</a>;</div>
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[1].<a class="code" href="classompl_1_1BinaryHeap.html#a99e2aec266c1746cf0f16aa763d00d7f">getComparisonOperator</a>().opt_ = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>.get();</div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[1].<a class="code" href="classompl_1_1BinaryHeap.html#a99e2aec266c1746cf0f16aa763d00d7f">getComparisonOperator</a>().heuristics_ = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a46469aa4f63eb64b41cc3fca8dc6d503">heuristics_</a>;</div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  </div>
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span>  <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>)</div>
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>.reset(tools::SelfConfig::getDefaultNearestNeighbors<BiDirMotion *>(<span class="keyword">this</span>));</div>
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->setDistanceFunction([<span class="keyword">this</span>](<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *a, <span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *b)</div>
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  {</div>
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span>  <span class="keywordflow">return</span> <a class="code" href="classompl_1_1geometric_1_1FMT.html#ac59c55a3e5e6b67e0fe7fa3e5e04ed86">distanceFunction</a>(a, b);</div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  });</div>
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span>  </div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a> && !<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->reportsSortedResults())</div>
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  {</div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"%s: NearestNeighbors datastructure does not return sorted solutions. Nearest K strategy "</span></div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  <span class="stringliteral">"disabled."</span>,</div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a> = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  }</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  }</div>
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span>  {</div>
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: problem definition is not set, deferring setup completion..."</span>, <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#adba44a4ee27079c5b258a2ebed719eed">setup_</a> = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  }</div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  }</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  </div>
<div class="line"><a name="l00092"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a3eb3a0b7a44d10d0396b156fb7701f36"> 92</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a3eb3a0b7a44d10d0396b156fb7701f36">BFMT::freeMemory</a>()</div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  {</div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>)</div>
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span>  {</div>
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  BiDirMotionPtrs motions;</div>
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->list(motions);</div>
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  {</div>
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->freeState(motion->getState());</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <span class="keyword">delete</span> motion;</div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  }</div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  }</div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  }</div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  </div>
<div class="line"><a name="l00106"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#ae09fb8ea881f62673b33030ad50de93d"> 106</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#ae09fb8ea881f62673b33030ad50de93d">BFMT::clear</a>()</div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  {</div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  Planner::clear();</div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a9f9dd746c6cb063687e266617c4b1c29">sampler_</a>.reset();</div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a78b1fd3cfca7f4c32f2d3bf3a1fa5172">freeMemory</a>();</div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>)</div>
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->clear();</div>
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[FWD].<a class="code" href="classompl_1_1BinaryHeap.html#addf7a2e9d0cc43dd05659686f58d695f">clear</a>();</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[REV].<a class="code" href="classompl_1_1BinaryHeap.html#addf7a2e9d0cc43dd05659686f58d695f">clear</a>();</div>
<div class="line"><a name="l00115"></a><span class="lineno"> 115</span>  Open_elements[FWD].clear();</div>
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span>  Open_elements[REV].clear();</div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>.clear();</div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#ac2363aeafad97afc4dca4da81d4465f6">collisionChecks_</a> = 0;</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  }</div>
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span>  </div>
<div class="line"><a name="l00121"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a351cc4241d51cd48eee029c3b15f89f0"> 121</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a351cc4241d51cd48eee029c3b15f89f0">BFMT::getPlannerData</a>(<a class="code" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> &data)<span class="keyword"> const</span></div>
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#ae8af389dbcdf416e142dc2f1cf5a8829">base::Planner::getPlannerData</a>(data);</div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  BiDirMotionPtrs motions;</div>
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->list(motions);</div>
<div class="line"><a name="l00126"></a><span class="lineno"> 126</span>  </div>
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  <span class="keywordtype">int</span> fwd_tree_tag = 1;</div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="keywordtype">int</span> rev_tree_tag = 2;</div>
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  </div>
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> motion : motions)</div>
<div class="line"><a name="l00131"></a><span class="lineno"> 131</span>  {</div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span>  <span class="keywordtype">bool</span> inFwdTree = (motion->currentSet_[FWD] != BiDirMotion::SET_UNVISITED);</div>
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span>  </div>
<div class="line"><a name="l00134"></a><span class="lineno"> 134</span>  <span class="comment">// For samples added to the fwd tree, add incoming edges (from fwd tree parent)</span></div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span>  <span class="keywordflow">if</span> (inFwdTree)</div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span>  {</div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span>  <span class="keywordflow">if</span> (motion->parent_[FWD] != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  {</div>
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->parent_[FWD]->getState(), fwd_tree_tag),</div>
<div class="line"><a name="l00140"></a><span class="lineno"> 140</span>  <a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->getState(), fwd_tree_tag));</div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span>  }</div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span>  }</div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span>  }</div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  </div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span>  <span class="comment">// The edges in the goal tree are reversed so that they are in the same direction as start tree</span></div>
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> motion : motions)</div>
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span>  {</div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  <span class="keywordtype">bool</span> inRevTree = (motion->currentSet_[REV] != BiDirMotion::SET_UNVISITED);</div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  </div>
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span>  <span class="comment">// For samples added to a tree, add incoming edges (from fwd tree parent)</span></div>
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span>  <span class="keywordflow">if</span> (inRevTree)</div>
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span>  {</div>
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span>  <span class="keywordflow">if</span> (motion->parent_[REV] != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span>  {</div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->getState(), rev_tree_tag),</div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span>  <a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->parent_[REV]->getState(), rev_tree_tag));</div>
<div class="line"><a name="l00157"></a><span class="lineno"> 157</span>  }</div>
<div class="line"><a name="l00158"></a><span class="lineno"> 158</span>  }</div>
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span>  }</div>
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span>  }</div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  </div>
<div class="line"><a name="l00162"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#aa6d8c07d7dff93f8905490f606400b5d"> 162</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#aa6d8c07d7dff93f8905490f606400b5d">BFMT::saveNeighborhood</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *m)</div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  {</div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span>  <span class="comment">// Check if neighborhood has already been saved</span></div>
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>.find(m) == <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>.end())</div>
<div class="line"><a name="l00166"></a><span class="lineno"> 166</span>  {</div>
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  BiDirMotionPtrs neighborhood;</div>
<div class="line"><a name="l00168"></a><span class="lineno"> 168</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a>)</div>
<div class="line"><a name="l00169"></a><span class="lineno"> 169</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->nearestK(m, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a0728a9660b89e6fea28f6b3dff82d2d3">NNk_</a>, neighborhood);</div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->nearestR(m, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a72da258028ee6eafe239b4ba6cc4822c">NNr_</a>, neighborhood);</div>
<div class="line"><a name="l00172"></a><span class="lineno"> 172</span>  </div>
<div class="line"><a name="l00173"></a><span class="lineno"> 173</span>  <span class="keywordflow">if</span> (!neighborhood.empty())</div>
<div class="line"><a name="l00174"></a><span class="lineno"> 174</span>  {</div>
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  <span class="comment">// Save the neighborhood but skip the first element (m)</span></div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[m] = std::vector<BiDirMotion *>(neighborhood.size() - 1, <span class="keyword">nullptr</span>);</div>
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  std::copy(neighborhood.begin() + 1, neighborhood.end(), <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[m].begin());</div>
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  }</div>
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00180"></a><span class="lineno"> 180</span>  {</div>
<div class="line"><a name="l00181"></a><span class="lineno"> 181</span>  <span class="comment">// Save an empty neighborhood</span></div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[m] = std::vector<BiDirMotion *>(0);</div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span>  }</div>
<div class="line"><a name="l00184"></a><span class="lineno"> 184</span>  }</div>
<div class="line"><a name="l00185"></a><span class="lineno"> 185</span>  }</div>
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span>  </div>
<div class="line"><a name="l00187"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a7714fef9dc34c186c51360711b3eb11e"> 187</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a7714fef9dc34c186c51360711b3eb11e">BFMT::sampleFree</a>(<span class="keyword">const</span> std::shared_ptr<<a class="code" href="classompl_1_1NearestNeighbors.html">NearestNeighbors<BiDirMotion *></a>> &nn,</div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  {</div>
<div class="line"><a name="l00190"></a><span class="lineno"> 190</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> nodeCount = 0;</div>
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> sampleAttempts = 0;</div>
<div class="line"><a name="l00192"></a><span class="lineno"> 192</span>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, &tree_);</div>
<div class="line"><a name="l00193"></a><span class="lineno"> 193</span>  </div>
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  <span class="comment">// Sample numSamples_ number of nodes from the free configuration space</span></div>
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  <span class="keywordflow">while</span> (nodeCount < <a class="code" href="classompl_1_1geometric_1_1FMT.html#a4cf51874570d8086f93d84cdcf5afa38">numSamples_</a> && !ptc)</div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  {</div>
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a9f9dd746c6cb063687e266617c4b1c29">sampler_</a>->sampleUniform(motion->getState());</div>
<div class="line"><a name="l00198"></a><span class="lineno"> 198</span>  sampleAttempts++;</div>
<div class="line"><a name="l00199"></a><span class="lineno"> 199</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->isValid(motion->getState()))</div>
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span>  { <span class="comment">// collision checking</span></div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  ++nodeCount;</div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  nn->add(motion);</div>
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, &tree_);</div>
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  }</div>
<div class="line"><a name="l00205"></a><span class="lineno"> 205</span>  }</div>
<div class="line"><a name="l00206"></a><span class="lineno"> 206</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->freeState(motion->getState());</div>
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  <span class="keyword">delete</span> motion;</div>
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  </div>
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  <span class="comment">// 95% confidence limit for an upper bound for the true free space volume</span></div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a8dd5fe05d2383b43f96318afc8eb0be0">freeSpaceVolume_</a> =</div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  boost::math::binomial_distribution<>::find_upper_bound_on_p(sampleAttempts, nodeCount, 0.05) *</div>
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateSpace()->getMeasure();</div>
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  }</div>
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  </div>
<div class="line"><a name="l00215"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a830e4b62830ebd25708953de52b5abc0"> 215</a></span>  <span class="keywordtype">double</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a830e4b62830ebd25708953de52b5abc0">BFMT::calculateUnitBallVolume</a>(<span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> dimension)<span class="keyword"> const</span></div>
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  <span class="keywordflow">if</span> (dimension == 0)</div>
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span>  <span class="keywordflow">return</span> 1.0;</div>
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span>  <span class="keywordflow">if</span> (dimension == 1)</div>
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span>  <span class="keywordflow">return</span> 2.0;</div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span>  <span class="keywordflow">return</span> 2.0 * boost::math::constants::pi<double>() / dimension * <a class="code" href="classompl_1_1geometric_1_1FMT.html#ae9424eb55612abaab8b9109e62e76030">calculateUnitBallVolume</a>(dimension - 2);</div>
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span>  }</div>
<div class="line"><a name="l00223"></a><span class="lineno"> 223</span>  </div>
<div class="line"><a name="l00224"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a503a4265e428841344e620cf976b3b1f"> 224</a></span>  <span class="keywordtype">double</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a503a4265e428841344e620cf976b3b1f">BFMT::calculateRadius</a>(<span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> dimension, <span class="keyword">const</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> n)<span class="keyword"> const</span></div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00226"></a><span class="lineno"> 226</span>  <span class="keywordtype">double</span> a = 1.0 / (double)dimension;</div>
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span>  <span class="keywordtype">double</span> unitBallVolume = <a class="code" href="classompl_1_1geometric_1_1FMT.html#ae9424eb55612abaab8b9109e62e76030">calculateUnitBallVolume</a>(dimension);</div>
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  </div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  <span class="keywordflow">return</span> <a class="code" href="classompl_1_1geometric_1_1FMT.html#a46d97fd804d843808f96973d8428665a">radiusMultiplier_</a> * 2.0 * std::pow(a, a) * std::pow(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a8dd5fe05d2383b43f96318afc8eb0be0">freeSpaceVolume_</a> / unitBallVolume, a) *</div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span>  std::pow(<a class="code" href="namespaceompl_1_1msg.html#affe7852f27c06f98af7eb2579f1e5350">log</a>((<span class="keywordtype">double</span>)n) / (<span class="keywordtype">double</span>)n, a);</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  }</div>
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span>  </div>
<div class="line"><a name="l00233"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a6c4398da349abf2fb41a5bd884e0e1ce"> 233</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a6c4398da349abf2fb41a5bd884e0e1ce">BFMT::initializeProblem</a>(<a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *&goal_s)</div>
<div class="line"><a name="l00234"></a><span class="lineno"> 234</span>  {</div>
<div class="line"><a name="l00235"></a><span class="lineno"> 235</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#ab416900477cf4499139c01f35663dffb">checkValidity</a>();</div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1geometric_1_1FMT.html#a9f9dd746c6cb063687e266617c4b1c29">sampler_</a>)</div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  {</div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a9f9dd746c6cb063687e266617c4b1c29">sampler_</a> = <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->allocStateSampler();</div>
<div class="line"><a name="l00239"></a><span class="lineno"> 239</span>  }</div>
<div class="line"><a name="l00240"></a><span class="lineno"> 240</span>  goal_s = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *<span class="keyword">></span>(<a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->getGoal().get());</div>
<div class="line"><a name="l00241"></a><span class="lineno"> 241</span>  }</div>
<div class="line"><a name="l00242"></a><span class="lineno"> 242</span>  </div>
<div class="line"><a name="l00243"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#ac1c8420833341090cfd0086dea1db890"> 243</a></span>  <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">base::PlannerStatus</a> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#ac1c8420833341090cfd0086dea1db890">BFMT::solve</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  {</div>
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  <a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *goal_s;</div>
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  initializeProblem(goal_s);</div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  <span class="keywordflow">if</span> (goal_s == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  {</div>
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Unknown type of goal"</span>, <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a47d769205044efa345184a640bd863ff">base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE</a>;</div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  }</div>
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span>  </div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span>  useFwdTree();</div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  </div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  <span class="comment">// Add start states to Unvisitedfwd and Openfwd</span></div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  <span class="keywordtype">bool</span> valid_initMotion = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *initMotion;</div>
<div class="line"><a name="l00258"></a><span class="lineno"> 258</span>  <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *st = <a class="code" href="classompl_1_1base_1_1Planner.html#a1c6ac45d44026aae6df87f3295d67436">pis_</a>.<a class="code" href="classompl_1_1base_1_1PlannerInputStates.html#a42a3a7bdbbe09caf937e57785ee97d51">nextStart</a>())</div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  {</div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span>  initMotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, &tree_);</div>
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->copyState(initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>(), st);</div>
<div class="line"><a name="l00262"></a><span class="lineno"> 262</span>  </div>
<div class="line"><a name="l00263"></a><span class="lineno"> 263</span>  initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad05948bc009ecf7aa580a0e880a35951">currentSet_</a>[REV] = BiDirMotion::SET_UNVISITED;</div>
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->add(initMotion); <span class="comment">// S <-- {x_init}</span></div>
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->isValid(initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>()))</div>
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  {</div>
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span>  <span class="comment">// Take the first valid initial state as the forward tree root</span></div>
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span>  Open_elements[FWD][initMotion] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[FWD].<a class="code" href="classompl_1_1BinaryHeap.html#a7712c8909b596a4d12e0080960bd0274">insert</a>(initMotion);</div>
<div class="line"><a name="l00269"></a><span class="lineno"> 269</span>  initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad05948bc009ecf7aa580a0e880a35951">currentSet_</a>[FWD] = BiDirMotion::SET_OPEN;</div>
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span>  initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a7192d0242567b1ba8093445e2598d9b4">cost_</a>[FWD] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->initialCost(initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>());</div>
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span>  valid_initMotion = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span>  heurGoalState_[1] = initMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>();</div>
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span>  }</div>
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span>  }</div>
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span>  </div>
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  <span class="keywordflow">if</span> ((initMotion == <span class="keyword">nullptr</span>) || !valid_initMotion)</div>
<div class="line"><a name="l00277"></a><span class="lineno"> 277</span>  {</div>
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Start state undefined or invalid."</span>);</div>
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a1f20d012b563fc223902e24a8bcd7547">base::PlannerStatus::INVALID_START</a>;</div>
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  }</div>
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  </div>
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  <span class="comment">// Sample N free states in configuration state_</span></div>
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a61887b3a9a652085c2086491455b26c0">sampleFree</a>(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>, ptc); <span class="comment">// S <-- SAMPLEFREE(N)</span></div>
<div class="line"><a name="l00284"></a><span class="lineno"> 284</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Starting planning with %u states already in datastructure"</span>, <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str(),</div>
<div class="line"><a name="l00285"></a><span class="lineno"> 285</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->size());</div>
<div class="line"><a name="l00286"></a><span class="lineno"> 286</span>  </div>
<div class="line"><a name="l00287"></a><span class="lineno"> 287</span>  <span class="comment">// Calculate the nearest neighbor search radius</span></div>
<div class="line"><a name="l00288"></a><span class="lineno"> 288</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a>)</div>
<div class="line"><a name="l00289"></a><span class="lineno"> 289</span>  {</div>
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a0728a9660b89e6fea28f6b3dff82d2d3">NNk_</a> = std::ceil(std::pow(2.0 * <a class="code" href="classompl_1_1geometric_1_1FMT.html#a46d97fd804d843808f96973d8428665a">radiusMultiplier_</a>, (<span class="keywordtype">double</span>)<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateDimension()) *</div>
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  (boost::math::constants::e<double>() / (<span class="keywordtype">double</span>)<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateDimension()) *</div>
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span>  <a class="code" href="namespaceompl_1_1msg.html#affe7852f27c06f98af7eb2579f1e5350">log</a>((<span class="keywordtype">double</span>)<a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->size()));</div>
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  <a class="code" href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a>(<span class="stringliteral">"Using nearest-neighbors k of %d"</span>, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a0728a9660b89e6fea28f6b3dff82d2d3">NNk_</a>);</div>
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span>  }</div>
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span>  {</div>
<div class="line"><a name="l00297"></a><span class="lineno"> 297</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a72da258028ee6eafe239b4ba6cc4822c">NNr_</a> = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a3005a2f74ee6f5aee29a4af9547359a4">calculateRadius</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateDimension(), <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->size());</div>
<div class="line"><a name="l00298"></a><span class="lineno"> 298</span>  <a class="code" href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a>(<span class="stringliteral">"Using radius of %f"</span>, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a72da258028ee6eafe239b4ba6cc4822c">NNr_</a>);</div>
<div class="line"><a name="l00299"></a><span class="lineno"> 299</span>  }</div>
<div class="line"><a name="l00300"></a><span class="lineno"> 300</span>  </div>
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span>  <span class="comment">// Add goal states to Unvisitedrev and Openrev</span></div>
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span>  <span class="keywordtype">bool</span> valid_goalMotion = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *goalMotion;</div>
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span>  <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *st = <a class="code" href="classompl_1_1base_1_1Planner.html#a1c6ac45d44026aae6df87f3295d67436">pis_</a>.<a class="code" href="classompl_1_1base_1_1PlannerInputStates.html#ae8ea1c2fd3e0e92dbc289a79dd597c98">nextGoal</a>())</div>
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span>  {</div>
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span>  goalMotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, &tree_);</div>
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->copyState(goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>(), st);</div>
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span>  </div>
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span>  goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad05948bc009ecf7aa580a0e880a35951">currentSet_</a>[FWD] = BiDirMotion::SET_UNVISITED;</div>
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->add(goalMotion); <span class="comment">// S <-- {x_goal}</span></div>
<div class="line"><a name="l00311"></a><span class="lineno"> 311</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->isValid(goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>()))</div>
<div class="line"><a name="l00312"></a><span class="lineno"> 312</span>  {</div>
<div class="line"><a name="l00313"></a><span class="lineno"> 313</span>  <span class="comment">// Take the first valid goal state as the reverse tree root</span></div>
<div class="line"><a name="l00314"></a><span class="lineno"> 314</span>  Open_elements[REV][goalMotion] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[REV].<a class="code" href="classompl_1_1BinaryHeap.html#a7712c8909b596a4d12e0080960bd0274">insert</a>(goalMotion);</div>
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span>  goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad05948bc009ecf7aa580a0e880a35951">currentSet_</a>[REV] = BiDirMotion::SET_OPEN;</div>
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span>  goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a7192d0242567b1ba8093445e2598d9b4">cost_</a>[REV] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->terminalCost(goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>());</div>
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span>  valid_goalMotion = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span>  heurGoalState_[0] = goalMotion-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>();</div>
<div class="line"><a name="l00319"></a><span class="lineno"> 319</span>  }</div>
<div class="line"><a name="l00320"></a><span class="lineno"> 320</span>  }</div>
<div class="line"><a name="l00321"></a><span class="lineno"> 321</span>  </div>
<div class="line"><a name="l00322"></a><span class="lineno"> 322</span>  <span class="keywordflow">if</span> ((goalMotion == <span class="keyword">nullptr</span>) || !valid_goalMotion)</div>
<div class="line"><a name="l00323"></a><span class="lineno"> 323</span>  {</div>
<div class="line"><a name="l00324"></a><span class="lineno"> 324</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Goal state undefined or invalid."</span>);</div>
<div class="line"><a name="l00325"></a><span class="lineno"> 325</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a2e2b2b7e02900c4417af0ecea272c637">base::PlannerStatus::INVALID_GOAL</a>;</div>
<div class="line"><a name="l00326"></a><span class="lineno"> 326</span>  }</div>
<div class="line"><a name="l00327"></a><span class="lineno"> 327</span>  </div>
<div class="line"><a name="l00328"></a><span class="lineno"> 328</span>  useRevTree();</div>
<div class="line"><a name="l00329"></a><span class="lineno"> 329</span>  </div>
<div class="line"><a name="l00330"></a><span class="lineno"> 330</span>  <span class="comment">// Plan a path</span></div>
<div class="line"><a name="l00331"></a><span class="lineno"> 331</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *connection_point = <span class="keyword">nullptr</span>;</div>
<div class="line"><a name="l00332"></a><span class="lineno"> 332</span>  <span class="keywordtype">bool</span> earlyFailure = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00333"></a><span class="lineno"> 333</span>  </div>
<div class="line"><a name="l00334"></a><span class="lineno"> 334</span>  <span class="keywordflow">if</span> (initMotion != <span class="keyword">nullptr</span> && goalMotion != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00335"></a><span class="lineno"> 335</span>  {</div>
<div class="line"><a name="l00336"></a><span class="lineno"> 336</span>  earlyFailure = plan(initMotion, goalMotion, connection_point, ptc);</div>
<div class="line"><a name="l00337"></a><span class="lineno"> 337</span>  }</div>
<div class="line"><a name="l00338"></a><span class="lineno"> 338</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00339"></a><span class="lineno"> 339</span>  {</div>
<div class="line"><a name="l00340"></a><span class="lineno"> 340</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Initial/goal state(s) are undefined!"</span>);</div>
<div class="line"><a name="l00341"></a><span class="lineno"> 341</span>  }</div>
<div class="line"><a name="l00342"></a><span class="lineno"> 342</span>  </div>
<div class="line"><a name="l00343"></a><span class="lineno"> 343</span>  <span class="keywordflow">if</span> (earlyFailure)</div>
<div class="line"><a name="l00344"></a><span class="lineno"> 344</span>  {</div>
<div class="line"><a name="l00345"></a><span class="lineno"> 345</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">base::PlannerStatus</a>(<span class="keyword">false</span>, <span class="keyword">false</span>);</div>
<div class="line"><a name="l00346"></a><span class="lineno"> 346</span>  }</div>
<div class="line"><a name="l00347"></a><span class="lineno"> 347</span>  </div>
<div class="line"><a name="l00348"></a><span class="lineno"> 348</span>  <span class="comment">// Save the best path (through z)</span></div>
<div class="line"><a name="l00349"></a><span class="lineno"> 349</span>  <span class="keywordflow">if</span> (!ptc)</div>
<div class="line"><a name="l00350"></a><span class="lineno"> 350</span>  {</div>
<div class="line"><a name="l00351"></a><span class="lineno"> 351</span>  <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> fwd_cost, rev_cost, connection_cost;</div>
<div class="line"><a name="l00352"></a><span class="lineno"> 352</span>  </div>
<div class="line"><a name="l00353"></a><span class="lineno"> 353</span>  <span class="comment">// Construct the solution path</span></div>
<div class="line"><a name="l00354"></a><span class="lineno"> 354</span>  useFwdTree();</div>
<div class="line"><a name="l00355"></a><span class="lineno"> 355</span>  BiDirMotionPtrs path_fwd;</div>
<div class="line"><a name="l00356"></a><span class="lineno"> 356</span>  tracePath(connection_point, path_fwd);</div>
<div class="line"><a name="l00357"></a><span class="lineno"> 357</span>  fwd_cost = connection_point-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#aea2f60e9b2e74bc178a0c821f49498c9">getCost</a>();</div>
<div class="line"><a name="l00358"></a><span class="lineno"> 358</span>  </div>
<div class="line"><a name="l00359"></a><span class="lineno"> 359</span>  useRevTree();</div>
<div class="line"><a name="l00360"></a><span class="lineno"> 360</span>  BiDirMotionPtrs path_rev;</div>
<div class="line"><a name="l00361"></a><span class="lineno"> 361</span>  tracePath(connection_point, path_rev);</div>
<div class="line"><a name="l00362"></a><span class="lineno"> 362</span>  rev_cost = connection_point-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#aea2f60e9b2e74bc178a0c821f49498c9">getCost</a>();</div>
<div class="line"><a name="l00363"></a><span class="lineno"> 363</span>  </div>
<div class="line"><a name="l00364"></a><span class="lineno"> 364</span>  <span class="comment">// ASSUMES FROM THIS POINT THAT z = path_fwd[0] = path_rev[0]</span></div>
<div class="line"><a name="l00365"></a><span class="lineno"> 365</span>  <span class="comment">// Remove the first element, z, in the traced reverse path</span></div>
<div class="line"><a name="l00366"></a><span class="lineno"> 366</span>  <span class="comment">// (the same as the first element in the traced forward path)</span></div>
<div class="line"><a name="l00367"></a><span class="lineno"> 367</span>  <span class="keywordflow">if</span> (path_rev.size() > 1)</div>
<div class="line"><a name="l00368"></a><span class="lineno"> 368</span>  {</div>
<div class="line"><a name="l00369"></a><span class="lineno"> 369</span>  connection_cost = <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(rev_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() - path_rev[1]->getCost().value());</div>
<div class="line"><a name="l00370"></a><span class="lineno"> 370</span>  path_rev.erase(path_rev.begin());</div>
<div class="line"><a name="l00371"></a><span class="lineno"> 371</span>  }</div>
<div class="line"><a name="l00372"></a><span class="lineno"> 372</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (path_fwd.size() > 1)</div>
<div class="line"><a name="l00373"></a><span class="lineno"> 373</span>  {</div>
<div class="line"><a name="l00374"></a><span class="lineno"> 374</span>  connection_cost = <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(fwd_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() - path_fwd[1]->getCost().value());</div>
<div class="line"><a name="l00375"></a><span class="lineno"> 375</span>  path_fwd.erase(path_fwd.begin());</div>
<div class="line"><a name="l00376"></a><span class="lineno"> 376</span>  }</div>
<div class="line"><a name="l00377"></a><span class="lineno"> 377</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00378"></a><span class="lineno"> 378</span>  {</div>
<div class="line"><a name="l00379"></a><span class="lineno"> 379</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Solution path traced incorrectly or otherwise constructed improperly \</span></div>
<div class="line"><a name="l00380"></a><span class="lineno"> 380</span> <span class="stringliteral"> through forward/reverse trees (both paths are one node in length, each)."</span>);</div>
<div class="line"><a name="l00381"></a><span class="lineno"> 381</span>  }</div>
<div class="line"><a name="l00382"></a><span class="lineno"> 382</span>  </div>
<div class="line"><a name="l00383"></a><span class="lineno"> 383</span>  <span class="comment">// Adjust costs/parents in reverse tree nodes as cost/direction from forward tree root</span></div>
<div class="line"><a name="l00384"></a><span class="lineno"> 384</span>  useFwdTree();</div>
<div class="line"><a name="l00385"></a><span class="lineno"> 385</span>  path_rev[0]->setCost(<a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(path_fwd[0]->getCost().value() + connection_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>()));</div>
<div class="line"><a name="l00386"></a><span class="lineno"> 386</span>  path_rev[0]->setParent(path_fwd[0]);</div>
<div class="line"><a name="l00387"></a><span class="lineno"> 387</span>  <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 1; i < path_rev.size(); ++i)</div>
<div class="line"><a name="l00388"></a><span class="lineno"> 388</span>  {</div>
<div class="line"><a name="l00389"></a><span class="lineno"> 389</span>  path_rev[i]->setCost(</div>
<div class="line"><a name="l00390"></a><span class="lineno"> 390</span>  <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(fwd_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() + (rev_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() - path_rev[i]->getCost().value())));</div>
<div class="line"><a name="l00391"></a><span class="lineno"> 391</span>  path_rev[i]->setParent(path_rev[i - 1]);</div>
<div class="line"><a name="l00392"></a><span class="lineno"> 392</span>  }</div>
<div class="line"><a name="l00393"></a><span class="lineno"> 393</span>  </div>
<div class="line"><a name="l00394"></a><span class="lineno"> 394</span>  BiDirMotionPtrs mpath;</div>
<div class="line"><a name="l00395"></a><span class="lineno"> 395</span>  std::reverse(path_rev.begin(), path_rev.end());</div>
<div class="line"><a name="l00396"></a><span class="lineno"> 396</span>  mpath.reserve(path_fwd.size() + path_rev.size()); <span class="comment">// preallocate memory</span></div>
<div class="line"><a name="l00397"></a><span class="lineno"> 397</span>  mpath.insert(mpath.end(), path_rev.begin(), path_rev.end());</div>
<div class="line"><a name="l00398"></a><span class="lineno"> 398</span>  mpath.insert(mpath.end(), path_fwd.begin(), path_fwd.end());</div>
<div class="line"><a name="l00399"></a><span class="lineno"> 399</span>  </div>
<div class="line"><a name="l00400"></a><span class="lineno"> 400</span>  <span class="comment">// Set the solution path</span></div>
<div class="line"><a name="l00401"></a><span class="lineno"> 401</span>  <span class="keyword">auto</span> path(std::make_shared<PathGeometric>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>));</div>
<div class="line"><a name="l00402"></a><span class="lineno"> 402</span>  <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath.size() - 1; i >= 0; --i)</div>
<div class="line"><a name="l00403"></a><span class="lineno"> 403</span>  {</div>
<div class="line"><a name="l00404"></a><span class="lineno"> 404</span>  path->append(mpath[i]->getState());</div>
<div class="line"><a name="l00405"></a><span class="lineno"> 405</span>  }</div>
<div class="line"><a name="l00406"></a><span class="lineno"> 406</span>  </div>
<div class="line"><a name="l00407"></a><span class="lineno"> 407</span>  <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">bool</span> approximate = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00408"></a><span class="lineno"> 408</span>  <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">double</span> cost_difference_from_goal = 0.0;</div>
<div class="line"><a name="l00409"></a><span class="lineno"> 409</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->addSolutionPath(path, approximate, cost_difference_from_goal, <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>());</div>
<div class="line"><a name="l00410"></a><span class="lineno"> 410</span>  </div>
<div class="line"><a name="l00411"></a><span class="lineno"> 411</span>  <a class="code" href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a>(<span class="stringliteral">"Total path cost: %f\n"</span>, fwd_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() + rev_cost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>());</div>
<div class="line"><a name="l00412"></a><span class="lineno"> 412</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">base::PlannerStatus</a>(<span class="keyword">true</span>, <span class="keyword">false</span>);</div>
<div class="line"><a name="l00413"></a><span class="lineno"> 413</span>  }</div>
<div class="line"><a name="l00414"></a><span class="lineno"> 414</span>  </div>
<div class="line"><a name="l00415"></a><span class="lineno"> 415</span>  <span class="comment">// Planner terminated without accomplishing goal</span></div>
<div class="line"><a name="l00416"></a><span class="lineno"> 416</span>  <span class="keywordflow">return</span> {<span class="keyword">false</span>, <span class="keyword">false</span>};</div>
<div class="line"><a name="l00417"></a><span class="lineno"> 417</span>  }</div>
<div class="line"><a name="l00418"></a><span class="lineno"> 418</span>  </div>
<div class="line"><a name="l00419"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a59a090351c3271964c2b2cc37b14ea56"> 419</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a59a090351c3271964c2b2cc37b14ea56">BFMT::expandTreeFromNode</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&z, <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&connection_point)</div>
<div class="line"><a name="l00420"></a><span class="lineno"> 420</span>  {</div>
<div class="line"><a name="l00421"></a><span class="lineno"> 421</span>  <span class="comment">// Define Opennew and set it to NULL</span></div>
<div class="line"><a name="l00422"></a><span class="lineno"> 422</span>  BiDirMotionPtrs Open_new;</div>
<div class="line"><a name="l00423"></a><span class="lineno"> 423</span>  </div>
<div class="line"><a name="l00424"></a><span class="lineno"> 424</span>  <span class="comment">// Define Znear as all unexplored nodes in the neighborhood around z</span></div>
<div class="line"><a name="l00425"></a><span class="lineno"> 425</span>  BiDirMotionPtrs zNear;</div>
<div class="line"><a name="l00426"></a><span class="lineno"> 426</span>  <span class="keyword">const</span> BiDirMotionPtrs &zNeighborhood = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[z];</div>
<div class="line"><a name="l00427"></a><span class="lineno"> 427</span>  </div>
<div class="line"><a name="l00428"></a><span class="lineno"> 428</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> i : zNeighborhood)</div>
<div class="line"><a name="l00429"></a><span class="lineno"> 429</span>  {</div>
<div class="line"><a name="l00430"></a><span class="lineno"> 430</span>  <span class="keywordflow">if</span> (i->getCurrentSet() == BiDirMotion::SET_UNVISITED)</div>
<div class="line"><a name="l00431"></a><span class="lineno"> 431</span>  {</div>
<div class="line"><a name="l00432"></a><span class="lineno"> 432</span>  zNear.push_back(i);</div>
<div class="line"><a name="l00433"></a><span class="lineno"> 433</span>  }</div>
<div class="line"><a name="l00434"></a><span class="lineno"> 434</span>  }</div>
<div class="line"><a name="l00435"></a><span class="lineno"> 435</span>  </div>
<div class="line"><a name="l00436"></a><span class="lineno"> 436</span>  <span class="comment">// For each node x in Znear</span></div>
<div class="line"><a name="l00437"></a><span class="lineno"> 437</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> x : zNear)</div>
<div class="line"><a name="l00438"></a><span class="lineno"> 438</span>  {</div>
<div class="line"><a name="l00439"></a><span class="lineno"> 439</span>  <span class="keywordflow">if</span> (!precomputeNN_)</div>
<div class="line"><a name="l00440"></a><span class="lineno"> 440</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a257fcb8c64559bc2514493878e25675a">saveNeighborhood</a>(x); <span class="comment">// nearest neighbors</span></div>
<div class="line"><a name="l00441"></a><span class="lineno"> 441</span>  </div>
<div class="line"><a name="l00442"></a><span class="lineno"> 442</span>  <span class="comment">// Define Xnear as all frontier nodes in the neighborhood around the unexplored node x</span></div>
<div class="line"><a name="l00443"></a><span class="lineno"> 443</span>  BiDirMotionPtrs xNear;</div>
<div class="line"><a name="l00444"></a><span class="lineno"> 444</span>  <span class="keyword">const</span> BiDirMotionPtrs &xNeighborhood = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[x];</div>
<div class="line"><a name="l00445"></a><span class="lineno"> 445</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> j : xNeighborhood)</div>
<div class="line"><a name="l00446"></a><span class="lineno"> 446</span>  {</div>
<div class="line"><a name="l00447"></a><span class="lineno"> 447</span>  <span class="keywordflow">if</span> (j->getCurrentSet() == BiDirMotion::SET_OPEN)</div>
<div class="line"><a name="l00448"></a><span class="lineno"> 448</span>  {</div>
<div class="line"><a name="l00449"></a><span class="lineno"> 449</span>  xNear.push_back(j);</div>
<div class="line"><a name="l00450"></a><span class="lineno"> 450</span>  }</div>
<div class="line"><a name="l00451"></a><span class="lineno"> 451</span>  }</div>
<div class="line"><a name="l00452"></a><span class="lineno"> 452</span>  <span class="comment">// Find the node in Xnear with minimum cost-to-come in the current tree</span></div>
<div class="line"><a name="l00453"></a><span class="lineno"> 453</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *xMin = <span class="keyword">nullptr</span>;</div>
<div class="line"><a name="l00454"></a><span class="lineno"> 454</span>  <span class="keywordtype">double</span> cMin = std::numeric_limits<double>::infinity();</div>
<div class="line"><a name="l00455"></a><span class="lineno"> 455</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &j : xNear)</div>
<div class="line"><a name="l00456"></a><span class="lineno"> 456</span>  {</div>
<div class="line"><a name="l00457"></a><span class="lineno"> 457</span>  <span class="comment">// check if node costs are smaller than minimum</span></div>
<div class="line"><a name="l00458"></a><span class="lineno"> 458</span>  <span class="keywordtype">double</span> cNew = j->getCost().value() + <a class="code" href="classompl_1_1geometric_1_1FMT.html#ac59c55a3e5e6b67e0fe7fa3e5e04ed86">distanceFunction</a>(j, x);</div>
<div class="line"><a name="l00459"></a><span class="lineno"> 459</span>  </div>
<div class="line"><a name="l00460"></a><span class="lineno"> 460</span>  <span class="keywordflow">if</span> (cNew < cMin)</div>
<div class="line"><a name="l00461"></a><span class="lineno"> 461</span>  {</div>
<div class="line"><a name="l00462"></a><span class="lineno"> 462</span>  xMin = j;</div>
<div class="line"><a name="l00463"></a><span class="lineno"> 463</span>  cMin = cNew;</div>
<div class="line"><a name="l00464"></a><span class="lineno"> 464</span>  }</div>
<div class="line"><a name="l00465"></a><span class="lineno"> 465</span>  }</div>
<div class="line"><a name="l00466"></a><span class="lineno"> 466</span>  </div>
<div class="line"><a name="l00467"></a><span class="lineno"> 467</span>  <span class="comment">// xMin was found</span></div>
<div class="line"><a name="l00468"></a><span class="lineno"> 468</span>  <span class="keywordflow">if</span> (xMin != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00469"></a><span class="lineno"> 469</span>  {</div>
<div class="line"><a name="l00470"></a><span class="lineno"> 470</span>  <span class="keywordtype">bool</span> collision_free = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00471"></a><span class="lineno"> 471</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a3dcccb245843c4a244af2bb2fc8accb8">cacheCC_</a>)</div>
<div class="line"><a name="l00472"></a><span class="lineno"> 472</span>  {</div>
<div class="line"><a name="l00473"></a><span class="lineno"> 473</span>  <span class="keywordflow">if</span> (!xMin-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a321da3cf04df15cc6f76bd21fd2cb9f7">alreadyCC</a>(x))</div>
<div class="line"><a name="l00474"></a><span class="lineno"> 474</span>  {</div>
<div class="line"><a name="l00475"></a><span class="lineno"> 475</span>  collision_free = <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->checkMotion(xMin-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>(), x->getState());</div>
<div class="line"><a name="l00476"></a><span class="lineno"> 476</span>  ++<a class="code" href="classompl_1_1geometric_1_1FMT.html#ac2363aeafad97afc4dca4da81d4465f6">collisionChecks_</a>;</div>
<div class="line"><a name="l00477"></a><span class="lineno"> 477</span>  <span class="comment">// Due to FMT3* design, it is only necessary to save unsuccesful</span></div>
<div class="line"><a name="l00478"></a><span class="lineno"> 478</span>  <span class="comment">// connection attemps because of collision</span></div>
<div class="line"><a name="l00479"></a><span class="lineno"> 479</span>  <span class="keywordflow">if</span> (!collision_free)</div>
<div class="line"><a name="l00480"></a><span class="lineno"> 480</span>  xMin-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#acb3c3e761fe74aa4ab2645216046cdd2">addCC</a>(x);</div>
<div class="line"><a name="l00481"></a><span class="lineno"> 481</span>  }</div>
<div class="line"><a name="l00482"></a><span class="lineno"> 482</span>  }</div>
<div class="line"><a name="l00483"></a><span class="lineno"> 483</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00484"></a><span class="lineno"> 484</span>  {</div>
<div class="line"><a name="l00485"></a><span class="lineno"> 485</span>  ++<a class="code" href="classompl_1_1geometric_1_1FMT.html#ac2363aeafad97afc4dca4da81d4465f6">collisionChecks_</a>;</div>
<div class="line"><a name="l00486"></a><span class="lineno"> 486</span>  collision_free = <a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->checkMotion(xMin-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>(), x->getState());</div>
<div class="line"><a name="l00487"></a><span class="lineno"> 487</span>  }</div>
<div class="line"><a name="l00488"></a><span class="lineno"> 488</span>  </div>
<div class="line"><a name="l00489"></a><span class="lineno"> 489</span>  <span class="keywordflow">if</span> (collision_free)</div>
<div class="line"><a name="l00490"></a><span class="lineno"> 490</span>  { <span class="comment">// motion between yMin and x is obstacle free</span></div>
<div class="line"><a name="l00491"></a><span class="lineno"> 491</span>  <span class="comment">// add edge from xMin to x</span></div>
<div class="line"><a name="l00492"></a><span class="lineno"> 492</span>  x->setParent(xMin);</div>
<div class="line"><a name="l00493"></a><span class="lineno"> 493</span>  x->setCost(<a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(cMin));</div>
<div class="line"><a name="l00494"></a><span class="lineno"> 494</span>  xMin-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ab3300f91916c19b2cf7a60e6a9e92a94">getChildren</a>().push_back(x);</div>
<div class="line"><a name="l00495"></a><span class="lineno"> 495</span>  </div>
<div class="line"><a name="l00496"></a><span class="lineno"> 496</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a46469aa4f63eb64b41cc3fca8dc6d503">heuristics_</a>)</div>
<div class="line"><a name="l00497"></a><span class="lineno"> 497</span>  x->setHeuristicCost(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCostHeuristic(x->getState(), heurGoalState_[tree_]));</div>
<div class="line"><a name="l00498"></a><span class="lineno"> 498</span>  </div>
<div class="line"><a name="l00499"></a><span class="lineno"> 499</span>  <span class="comment">// check if new node x is in the other tree; if so, save result</span></div>
<div class="line"><a name="l00500"></a><span class="lineno"> 500</span>  <span class="keywordflow">if</span> (x->getOtherSet() != BiDirMotion::SET_UNVISITED)</div>
<div class="line"><a name="l00501"></a><span class="lineno"> 501</span>  {</div>
<div class="line"><a name="l00502"></a><span class="lineno"> 502</span>  <span class="keywordflow">if</span> (connection_point == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00503"></a><span class="lineno"> 503</span>  {</div>
<div class="line"><a name="l00504"></a><span class="lineno"> 504</span>  connection_point = x;</div>
<div class="line"><a name="l00505"></a><span class="lineno"> 505</span>  <span class="keywordflow">if</span> (termination_ == FEASIBILITY)</div>
<div class="line"><a name="l00506"></a><span class="lineno"> 506</span>  {</div>
<div class="line"><a name="l00507"></a><span class="lineno"> 507</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00508"></a><span class="lineno"> 508</span>  }</div>
<div class="line"><a name="l00509"></a><span class="lineno"> 509</span>  }</div>
<div class="line"><a name="l00510"></a><span class="lineno"> 510</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00511"></a><span class="lineno"> 511</span>  {</div>
<div class="line"><a name="l00512"></a><span class="lineno"> 512</span>  <span class="keywordflow">if</span> ((connection_point-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a7192d0242567b1ba8093445e2598d9b4">cost_</a>[FWD].<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() + connection_point-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a7192d0242567b1ba8093445e2598d9b4">cost_</a>[REV].<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>()) ></div>
<div class="line"><a name="l00513"></a><span class="lineno"> 513</span>  (x->cost_[FWD].value() + x->cost_[REV].value()))</div>
<div class="line"><a name="l00514"></a><span class="lineno"> 514</span>  {</div>
<div class="line"><a name="l00515"></a><span class="lineno"> 515</span>  connection_point = x;</div>
<div class="line"><a name="l00516"></a><span class="lineno"> 516</span>  }</div>
<div class="line"><a name="l00517"></a><span class="lineno"> 517</span>  }</div>
<div class="line"><a name="l00518"></a><span class="lineno"> 518</span>  }</div>
<div class="line"><a name="l00519"></a><span class="lineno"> 519</span>  </div>
<div class="line"><a name="l00520"></a><span class="lineno"> 520</span>  Open_new.push_back(x); <span class="comment">// add x to Open_new</span></div>
<div class="line"><a name="l00521"></a><span class="lineno"> 521</span>  x->setCurrentSet(BiDirMotion::SET_CLOSED); <span class="comment">// remove x from Unvisited</span></div>
<div class="line"><a name="l00522"></a><span class="lineno"> 522</span>  }</div>
<div class="line"><a name="l00523"></a><span class="lineno"> 523</span>  }</div>
<div class="line"><a name="l00524"></a><span class="lineno"> 524</span>  } <span class="comment">// End "for x in Znear"</span></div>
<div class="line"><a name="l00525"></a><span class="lineno"> 525</span>  </div>
<div class="line"><a name="l00526"></a><span class="lineno"> 526</span>  <span class="comment">// Remove motion z from binary heap and map</span></div>
<div class="line"><a name="l00527"></a><span class="lineno"> 527</span>  BiDirMotionBinHeap::Element *zElement = Open_elements[tree_][z];</div>
<div class="line"><a name="l00528"></a><span class="lineno"> 528</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a56848811174698cd9a907e1128e6ce02">remove</a>(zElement);</div>
<div class="line"><a name="l00529"></a><span class="lineno"> 529</span>  Open_elements[tree_].erase(z);</div>
<div class="line"><a name="l00530"></a><span class="lineno"> 530</span>  z-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad9d60c80413cde10004e924f2210a68a">setCurrentSet</a>(BiDirMotion::SET_CLOSED);</div>
<div class="line"><a name="l00531"></a><span class="lineno"> 531</span>  </div>
<div class="line"><a name="l00532"></a><span class="lineno"> 532</span>  <span class="comment">// add nodes in Open_new to Open</span></div>
<div class="line"><a name="l00533"></a><span class="lineno"> 533</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &i : Open_new)</div>
<div class="line"><a name="l00534"></a><span class="lineno"> 534</span>  {</div>
<div class="line"><a name="l00535"></a><span class="lineno"> 535</span>  <span class="keywordflow">if</span>(Open_elements[tree_][i] == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00536"></a><span class="lineno"> 536</span>  {</div>
<div class="line"><a name="l00537"></a><span class="lineno"> 537</span>  Open_elements[tree_][i] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a7712c8909b596a4d12e0080960bd0274">insert</a>(i);</div>
<div class="line"><a name="l00538"></a><span class="lineno"> 538</span>  i->setCurrentSet(BiDirMotion::SET_OPEN);</div>
<div class="line"><a name="l00539"></a><span class="lineno"> 539</span>  }</div>
<div class="line"><a name="l00540"></a><span class="lineno"> 540</span>  }</div>
<div class="line"><a name="l00541"></a><span class="lineno"> 541</span>  }</div>
<div class="line"><a name="l00542"></a><span class="lineno"> 542</span>  </div>
<div class="line"><a name="l00543"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a1f040102281e7a67bb2e322e79d8212f"> 543</a></span>  <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a1f040102281e7a67bb2e322e79d8212f">BFMT::plan</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *x_init, <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *x_goal, <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&connection_point,</div>
<div class="line"><a name="l00544"></a><span class="lineno"> 544</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00545"></a><span class="lineno"> 545</span>  {</div>
<div class="line"><a name="l00546"></a><span class="lineno"> 546</span>  <span class="comment">// If pre-computation, find neighborhoods for all N sample nodes plus initial</span></div>
<div class="line"><a name="l00547"></a><span class="lineno"> 547</span>  <span class="comment">// and goal state(s). Otherwise compute the neighborhoods of the initial and</span></div>
<div class="line"><a name="l00548"></a><span class="lineno"> 548</span>  <span class="comment">// goal states separately and compute the others as needed.</span></div>
<div class="line"><a name="l00549"></a><span class="lineno"> 549</span>  BiDirMotionPtrs sampleNodes;</div>
<div class="line"><a name="l00550"></a><span class="lineno"> 550</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->list(sampleNodes);</div>
<div class="line"><a name="l00553"></a><span class="lineno"> 553</span>  <span class="keywordflow">if</span> (precomputeNN_)</div>
<div class="line"><a name="l00554"></a><span class="lineno"> 554</span>  {</div>
<div class="line"><a name="l00555"></a><span class="lineno"> 555</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &sampleNode : sampleNodes)</div>
<div class="line"><a name="l00556"></a><span class="lineno"> 556</span>  {</div>
<div class="line"><a name="l00557"></a><span class="lineno"> 557</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a257fcb8c64559bc2514493878e25675a">saveNeighborhood</a>(sampleNode); <span class="comment">// nearest neighbors</span></div>
<div class="line"><a name="l00558"></a><span class="lineno"> 558</span>  }</div>
<div class="line"><a name="l00559"></a><span class="lineno"> 559</span>  }</div>
<div class="line"><a name="l00560"></a><span class="lineno"> 560</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00561"></a><span class="lineno"> 561</span>  {</div>
<div class="line"><a name="l00562"></a><span class="lineno"> 562</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a257fcb8c64559bc2514493878e25675a">saveNeighborhood</a>(x_init); <span class="comment">// nearest neighbors</span></div>
<div class="line"><a name="l00563"></a><span class="lineno"> 563</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a257fcb8c64559bc2514493878e25675a">saveNeighborhood</a>(x_goal); <span class="comment">// nearest neighbors</span></div>
<div class="line"><a name="l00564"></a><span class="lineno"> 564</span>  }</div>
<div class="line"><a name="l00565"></a><span class="lineno"> 565</span>  </div>
<div class="line"><a name="l00566"></a><span class="lineno"> 566</span>  <span class="comment">// Copy nodes in the sample set to Unvisitedfwd. Overwrite the label of the initial</span></div>
<div class="line"><a name="l00567"></a><span class="lineno"> 567</span>  <span class="comment">// node with set Open for the forward tree, since it starts in set Openfwd.</span></div>
<div class="line"><a name="l00568"></a><span class="lineno"> 568</span>  useFwdTree();</div>
<div class="line"><a name="l00569"></a><span class="lineno"> 569</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &sampleNode : sampleNodes)</div>
<div class="line"><a name="l00570"></a><span class="lineno"> 570</span>  {</div>
<div class="line"><a name="l00571"></a><span class="lineno"> 571</span>  sampleNode->setCurrentSet(BiDirMotion::SET_UNVISITED);</div>
<div class="line"><a name="l00572"></a><span class="lineno"> 572</span>  }</div>
<div class="line"><a name="l00573"></a><span class="lineno"> 573</span>  x_init-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad9d60c80413cde10004e924f2210a68a">setCurrentSet</a>(BiDirMotion::SET_OPEN);</div>
<div class="line"><a name="l00574"></a><span class="lineno"> 574</span>  </div>
<div class="line"><a name="l00575"></a><span class="lineno"> 575</span>  <span class="comment">// Copy nodes in the sample set to Unvisitedrev. Overwrite the label of the goal</span></div>
<div class="line"><a name="l00576"></a><span class="lineno"> 576</span>  <span class="comment">// node with set Open for the reverse tree, since it starts in set Openrev.</span></div>
<div class="line"><a name="l00577"></a><span class="lineno"> 577</span>  useRevTree();</div>
<div class="line"><a name="l00578"></a><span class="lineno"> 578</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &sampleNode : sampleNodes)</div>
<div class="line"><a name="l00579"></a><span class="lineno"> 579</span>  {</div>
<div class="line"><a name="l00580"></a><span class="lineno"> 580</span>  sampleNode->setCurrentSet(BiDirMotion::SET_UNVISITED);</div>
<div class="line"><a name="l00581"></a><span class="lineno"> 581</span>  }</div>
<div class="line"><a name="l00582"></a><span class="lineno"> 582</span>  x_goal-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#ad9d60c80413cde10004e924f2210a68a">setCurrentSet</a>(BiDirMotion::SET_OPEN);</div>
<div class="line"><a name="l00583"></a><span class="lineno"> 583</span>  </div>
<div class="line"><a name="l00584"></a><span class="lineno"> 584</span>  <span class="comment">// Expand the trees until reaching the termination condition</span></div>
<div class="line"><a name="l00585"></a><span class="lineno"> 585</span>  <span class="keywordtype">bool</span> earlyFailure = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00586"></a><span class="lineno"> 586</span>  <span class="keywordtype">bool</span> success = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00587"></a><span class="lineno"> 587</span>  </div>
<div class="line"><a name="l00588"></a><span class="lineno"> 588</span>  useFwdTree();</div>
<div class="line"><a name="l00589"></a><span class="lineno"> 589</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *z = x_init;</div>
<div class="line"><a name="l00590"></a><span class="lineno"> 590</span>  </div>
<div class="line"><a name="l00591"></a><span class="lineno"> 591</span>  <span class="keywordflow">while</span> (!success)</div>
<div class="line"><a name="l00592"></a><span class="lineno"> 592</span>  {</div>
<div class="line"><a name="l00593"></a><span class="lineno"> 593</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#ac77f66e21b5d554fac36d1f8e5b58159">expandTreeFromNode</a>(z, connection_point);</div>
<div class="line"><a name="l00594"></a><span class="lineno"> 594</span>  </div>
<div class="line"><a name="l00595"></a><span class="lineno"> 595</span>  <span class="comment">// Check if the algorithm should terminate. Possibly redefines connection_point.</span></div>
<div class="line"><a name="l00596"></a><span class="lineno"> 596</span>  <span class="keywordflow">if</span> (termination(z, connection_point, ptc))</div>
<div class="line"><a name="l00597"></a><span class="lineno"> 597</span>  success = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00598"></a><span class="lineno"> 598</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00599"></a><span class="lineno"> 599</span>  {</div>
<div class="line"><a name="l00600"></a><span class="lineno"> 600</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].empty()) <span class="comment">// If this heap is empty...</span></div>
<div class="line"><a name="l00601"></a><span class="lineno"> 601</span>  {</div>
<div class="line"><a name="l00602"></a><span class="lineno"> 602</span>  <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1geometric_1_1FMT.html#adff4cf3f367615fc892ec60383f3230a">extendedFMT_</a>) <span class="comment">// ... eFMT not enabled...</span></div>
<div class="line"><a name="l00603"></a><span class="lineno"> 603</span>  {</div>
<div class="line"><a name="l00604"></a><span class="lineno"> 604</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].empty()) <span class="comment">// ... and this one, failure.</span></div>
<div class="line"><a name="l00605"></a><span class="lineno"> 605</span>  {</div>
<div class="line"><a name="l00606"></a><span class="lineno"> 606</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Both Open are empty before path was found --> no feasible path exists"</span>);</div>
<div class="line"><a name="l00607"></a><span class="lineno"> 607</span>  earlyFailure = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00608"></a><span class="lineno"> 608</span>  <span class="keywordflow">return</span> earlyFailure;</div>
<div class="line"><a name="l00609"></a><span class="lineno"> 609</span>  }</div>
<div class="line"><a name="l00610"></a><span class="lineno"> 610</span>  }</div>
<div class="line"><a name="l00611"></a><span class="lineno"> 611</span>  <span class="keywordflow">else</span> <span class="comment">// However, if eFMT is enabled, run it.</span></div>
<div class="line"><a name="l00612"></a><span class="lineno"> 612</span>  insertNewSampleInOpen(ptc);</div>
<div class="line"><a name="l00613"></a><span class="lineno"> 613</span>  }</div>
<div class="line"><a name="l00614"></a><span class="lineno"> 614</span>  </div>
<div class="line"><a name="l00615"></a><span class="lineno"> 615</span>  <span class="comment">// This function will be always reached with at least one state in one heap.</span></div>
<div class="line"><a name="l00616"></a><span class="lineno"> 616</span>  <span class="comment">// However, if ptc terminates, we should skip this.</span></div>
<div class="line"><a name="l00617"></a><span class="lineno"> 617</span>  <span class="keywordflow">if</span> (!ptc)</div>
<div class="line"><a name="l00618"></a><span class="lineno"> 618</span>  chooseTreeAndExpansionNode(z);</div>
<div class="line"><a name="l00619"></a><span class="lineno"> 619</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00620"></a><span class="lineno"> 620</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00621"></a><span class="lineno"> 621</span>  }</div>
<div class="line"><a name="l00622"></a><span class="lineno"> 622</span>  }</div>
<div class="line"><a name="l00623"></a><span class="lineno"> 623</span>  earlyFailure = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00624"></a><span class="lineno"> 624</span>  <span class="keywordflow">return</span> earlyFailure;</div>
<div class="line"><a name="l00625"></a><span class="lineno"> 625</span>  }</div>
<div class="line"><a name="l00626"></a><span class="lineno"> 626</span>  </div>
<div class="line"><a name="l00627"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a1b3c080a4a25462e8ff1684b614b5fd9"> 627</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a1b3c080a4a25462e8ff1684b614b5fd9">BFMT::insertNewSampleInOpen</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00628"></a><span class="lineno"> 628</span>  {</div>
<div class="line"><a name="l00629"></a><span class="lineno"> 629</span>  <span class="comment">// Sample and connect samples to tree only if there is</span></div>
<div class="line"><a name="l00630"></a><span class="lineno"> 630</span>  <span class="comment">// a possibility to connect to unvisited nodes.</span></div>
<div class="line"><a name="l00631"></a><span class="lineno"> 631</span>  std::vector<BiDirMotion *> nbh;</div>
<div class="line"><a name="l00632"></a><span class="lineno"> 632</span>  std::vector<base::Cost> costs;</div>
<div class="line"><a name="l00633"></a><span class="lineno"> 633</span>  std::vector<base::Cost> incCosts;</div>
<div class="line"><a name="l00634"></a><span class="lineno"> 634</span>  std::vector<std::size_t> sortedCostIndices;</div>
<div class="line"><a name="l00635"></a><span class="lineno"> 635</span>  </div>
<div class="line"><a name="l00636"></a><span class="lineno"> 636</span>  <span class="comment">// our functor for sorting nearest neighbors</span></div>
<div class="line"><a name="l00637"></a><span class="lineno"> 637</span>  <a class="code" href="structompl_1_1geometric_1_1BFMT_1_1CostIndexCompare.html">CostIndexCompare</a> compareFn(costs, *<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>);</div>
<div class="line"><a name="l00638"></a><span class="lineno"> 638</span>  </div>
<div class="line"><a name="l00639"></a><span class="lineno"> 639</span>  <span class="keyword">auto</span> *m = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a>(<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, &tree_);</div>
<div class="line"><a name="l00640"></a><span class="lineno"> 640</span>  <span class="keywordflow">while</span> (!ptc && <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].empty()) <span class="comment">//&& oneSample)</span></div>
<div class="line"><a name="l00641"></a><span class="lineno"> 641</span>  {</div>
<div class="line"><a name="l00642"></a><span class="lineno"> 642</span>  <span class="comment">// Get new sample and check whether it is valid.</span></div>
<div class="line"><a name="l00643"></a><span class="lineno"> 643</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a9f9dd746c6cb063687e266617c4b1c29">sampler_</a>->sampleUniform(m->getState());</div>
<div class="line"><a name="l00644"></a><span class="lineno"> 644</span>  <span class="keywordflow">if</span> (!<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->isValid(m->getState()))</div>
<div class="line"><a name="l00645"></a><span class="lineno"> 645</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00646"></a><span class="lineno"> 646</span>  </div>
<div class="line"><a name="l00647"></a><span class="lineno"> 647</span>  <span class="comment">// Get neighbours of the new sample.</span></div>
<div class="line"><a name="l00648"></a><span class="lineno"> 648</span>  std::vector<BiDirMotion *> yNear;</div>
<div class="line"><a name="l00649"></a><span class="lineno"> 649</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a>)</div>
<div class="line"><a name="l00650"></a><span class="lineno"> 650</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->nearestK(m, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a0728a9660b89e6fea28f6b3dff82d2d3">NNk_</a>, nbh);</div>
<div class="line"><a name="l00651"></a><span class="lineno"> 651</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00652"></a><span class="lineno"> 652</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->nearestR(m, <a class="code" href="classompl_1_1geometric_1_1FMT.html#a72da258028ee6eafe239b4ba6cc4822c">NNr_</a>, nbh);</div>
<div class="line"><a name="l00653"></a><span class="lineno"> 653</span>  </div>
<div class="line"><a name="l00654"></a><span class="lineno"> 654</span>  yNear.reserve(nbh.size());</div>
<div class="line"><a name="l00655"></a><span class="lineno"> 655</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &j : nbh)</div>
<div class="line"><a name="l00656"></a><span class="lineno"> 656</span>  {</div>
<div class="line"><a name="l00657"></a><span class="lineno"> 657</span>  <span class="keywordflow">if</span> (j->getCurrentSet() == BiDirMotion::SET_CLOSED)</div>
<div class="line"><a name="l00658"></a><span class="lineno"> 658</span>  {</div>
<div class="line"><a name="l00659"></a><span class="lineno"> 659</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a0f6a9a5969fc80fcf10e84ec46056a39">nearestK_</a>)</div>
<div class="line"><a name="l00660"></a><span class="lineno"> 660</span>  {</div>
<div class="line"><a name="l00661"></a><span class="lineno"> 661</span>  <span class="comment">// Only include neighbors that are mutually k-nearest</span></div>
<div class="line"><a name="l00662"></a><span class="lineno"> 662</span>  <span class="comment">// Relies on NN datastructure returning k-nearest in sorted order</span></div>
<div class="line"><a name="l00663"></a><span class="lineno"> 663</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> connCost = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(j->getState(), m->getState());</div>
<div class="line"><a name="l00664"></a><span class="lineno"> 664</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> worstCost =</div>
<div class="line"><a name="l00665"></a><span class="lineno"> 665</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>[j].back()->getState(), j->getState());</div>
<div class="line"><a name="l00666"></a><span class="lineno"> 666</span>  </div>
<div class="line"><a name="l00667"></a><span class="lineno"> 667</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->isCostBetterThan(worstCost, connCost))</div>
<div class="line"><a name="l00668"></a><span class="lineno"> 668</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00669"></a><span class="lineno"> 669</span>  yNear.push_back(j);</div>
<div class="line"><a name="l00670"></a><span class="lineno"> 670</span>  }</div>
<div class="line"><a name="l00671"></a><span class="lineno"> 671</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00672"></a><span class="lineno"> 672</span>  yNear.push_back(j);</div>
<div class="line"><a name="l00673"></a><span class="lineno"> 673</span>  }</div>
<div class="line"><a name="l00674"></a><span class="lineno"> 674</span>  }</div>
<div class="line"><a name="l00675"></a><span class="lineno"> 675</span>  </div>
<div class="line"><a name="l00676"></a><span class="lineno"> 676</span>  <span class="comment">// Sample again if the new sample does not connect to the tree.</span></div>
<div class="line"><a name="l00677"></a><span class="lineno"> 677</span>  <span class="keywordflow">if</span> (yNear.empty())</div>
<div class="line"><a name="l00678"></a><span class="lineno"> 678</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00679"></a><span class="lineno"> 679</span>  </div>
<div class="line"><a name="l00680"></a><span class="lineno"> 680</span>  <span class="comment">// cache for distance computations</span></div>
<div class="line"><a name="l00681"></a><span class="lineno"> 681</span>  <span class="comment">//</span></div>
<div class="line"><a name="l00682"></a><span class="lineno"> 682</span>  <span class="comment">// Our cost caches only increase in size, so they're only</span></div>
<div class="line"><a name="l00683"></a><span class="lineno"> 683</span>  <span class="comment">// resized if they can't fit the current neighborhood</span></div>
<div class="line"><a name="l00684"></a><span class="lineno"> 684</span>  <span class="keywordflow">if</span> (costs.size() < yNear.size())</div>
<div class="line"><a name="l00685"></a><span class="lineno"> 685</span>  {</div>
<div class="line"><a name="l00686"></a><span class="lineno"> 686</span>  costs.resize(yNear.size());</div>
<div class="line"><a name="l00687"></a><span class="lineno"> 687</span>  incCosts.resize(yNear.size());</div>
<div class="line"><a name="l00688"></a><span class="lineno"> 688</span>  sortedCostIndices.resize(yNear.size());</div>
<div class="line"><a name="l00689"></a><span class="lineno"> 689</span>  }</div>
<div class="line"><a name="l00690"></a><span class="lineno"> 690</span>  </div>
<div class="line"><a name="l00691"></a><span class="lineno"> 691</span>  <span class="comment">// Finding the nearest neighbor to connect to</span></div>
<div class="line"><a name="l00692"></a><span class="lineno"> 692</span>  <span class="comment">// By default, neighborhood states are sorted by cost, and collision checking</span></div>
<div class="line"><a name="l00693"></a><span class="lineno"> 693</span>  <span class="comment">// is performed in increasing order of cost</span></div>
<div class="line"><a name="l00694"></a><span class="lineno"> 694</span>  <span class="comment">//</span></div>
<div class="line"><a name="l00695"></a><span class="lineno"> 695</span>  <span class="comment">// calculate all costs and distances</span></div>
<div class="line"><a name="l00696"></a><span class="lineno"> 696</span>  <span class="keywordflow">for</span> (std::size_t i = 0; i < yNear.size(); ++i)</div>
<div class="line"><a name="l00697"></a><span class="lineno"> 697</span>  {</div>
<div class="line"><a name="l00698"></a><span class="lineno"> 698</span>  incCosts[i] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(yNear[i]->getState(), m->getState());</div>
<div class="line"><a name="l00699"></a><span class="lineno"> 699</span>  costs[i] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->combineCosts(yNear[i]->getCost(), incCosts[i]);</div>
<div class="line"><a name="l00700"></a><span class="lineno"> 700</span>  }</div>
<div class="line"><a name="l00701"></a><span class="lineno"> 701</span>  </div>
<div class="line"><a name="l00702"></a><span class="lineno"> 702</span>  <span class="comment">// sort the nodes</span></div>
<div class="line"><a name="l00703"></a><span class="lineno"> 703</span>  <span class="comment">//</span></div>
<div class="line"><a name="l00704"></a><span class="lineno"> 704</span>  <span class="comment">// we're using index-value pairs so that we can get at</span></div>
<div class="line"><a name="l00705"></a><span class="lineno"> 705</span>  <span class="comment">// original, unsorted indices</span></div>
<div class="line"><a name="l00706"></a><span class="lineno"> 706</span>  <span class="keywordflow">for</span> (std::size_t i = 0; i < yNear.size(); ++i)</div>
<div class="line"><a name="l00707"></a><span class="lineno"> 707</span>  sortedCostIndices[i] = i;</div>
<div class="line"><a name="l00708"></a><span class="lineno"> 708</span>  std::sort(sortedCostIndices.begin(), sortedCostIndices.begin() + yNear.size(), compareFn);</div>
<div class="line"><a name="l00709"></a><span class="lineno"> 709</span>  </div>
<div class="line"><a name="l00710"></a><span class="lineno"> 710</span>  <span class="comment">// collision check until a valid motion is found</span></div>
<div class="line"><a name="l00711"></a><span class="lineno"> 711</span>  <span class="keywordflow">for</span> (std::vector<std::size_t>::const_iterator i = sortedCostIndices.begin();</div>
<div class="line"><a name="l00712"></a><span class="lineno"> 712</span>  i != sortedCostIndices.begin() + yNear.size(); ++i)</div>
<div class="line"><a name="l00713"></a><span class="lineno"> 713</span>  {</div>
<div class="line"><a name="l00714"></a><span class="lineno"> 714</span>  ++<a class="code" href="classompl_1_1geometric_1_1FMT.html#ac2363aeafad97afc4dca4da81d4465f6">collisionChecks_</a>;</div>
<div class="line"><a name="l00715"></a><span class="lineno"> 715</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->checkMotion(yNear[*i]->getState(), m->getState()))</div>
<div class="line"><a name="l00716"></a><span class="lineno"> 716</span>  {</div>
<div class="line"><a name="l00717"></a><span class="lineno"> 717</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> incCost = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(yNear[*i]->getState(), m->getState());</div>
<div class="line"><a name="l00718"></a><span class="lineno"> 718</span>  m->setParent(yNear[*i]);</div>
<div class="line"><a name="l00719"></a><span class="lineno"> 719</span>  yNear[*i]->getChildren().push_back(m);</div>
<div class="line"><a name="l00720"></a><span class="lineno"> 720</span>  m->setCost(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->combineCosts(yNear[*i]->getCost(), incCost));</div>
<div class="line"><a name="l00721"></a><span class="lineno"> 721</span>  m->setHeuristicCost(<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCostHeuristic(m->getState(), heurGoalState_[tree_]));</div>
<div class="line"><a name="l00722"></a><span class="lineno"> 722</span>  m->setCurrentSet(BiDirMotion::SET_OPEN);</div>
<div class="line"><a name="l00723"></a><span class="lineno"> 723</span>  Open_elements[tree_][m] = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a7712c8909b596a4d12e0080960bd0274">insert</a>(m);</div>
<div class="line"><a name="l00724"></a><span class="lineno"> 724</span>  </div>
<div class="line"><a name="l00725"></a><span class="lineno"> 725</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a420c86eff7b00b7ec20e79ecb2acee66">nn_</a>->add(m);</div>
<div class="line"><a name="l00726"></a><span class="lineno"> 726</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a257fcb8c64559bc2514493878e25675a">saveNeighborhood</a>(m);</div>
<div class="line"><a name="l00727"></a><span class="lineno"> 727</span>  <a class="code" href="classompl_1_1geometric_1_1FMT.html#a58e71b64488c88d447cbcfd1296b4812">updateNeighborhood</a>(m, nbh);</div>
<div class="line"><a name="l00728"></a><span class="lineno"> 728</span>  </div>
<div class="line"><a name="l00729"></a><span class="lineno"> 729</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00730"></a><span class="lineno"> 730</span>  }</div>
<div class="line"><a name="l00731"></a><span class="lineno"> 731</span>  }</div>
<div class="line"><a name="l00732"></a><span class="lineno"> 732</span>  } <span class="comment">// While Open_[tree_] empty</span></div>
<div class="line"><a name="l00733"></a><span class="lineno"> 733</span>  }</div>
<div class="line"><a name="l00734"></a><span class="lineno"> 734</span>  </div>
<div class="line"><a name="l00735"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a308deda6599cfbca27cd273f8cc90dbb"> 735</a></span>  <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a308deda6599cfbca27cd273f8cc90dbb">BFMT::termination</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&z, <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&connection_point,</div>
<div class="line"><a name="l00736"></a><span class="lineno"> 736</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00737"></a><span class="lineno"> 737</span>  {</div>
<div class="line"><a name="l00738"></a><span class="lineno"> 738</span>  <span class="keywordtype">bool</span> terminate = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00739"></a><span class="lineno"> 739</span>  <span class="keywordflow">switch</span> (termination_)</div>
<div class="line"><a name="l00740"></a><span class="lineno"> 740</span>  {</div>
<div class="line"><a name="l00741"></a><span class="lineno"> 741</span>  <span class="keywordflow">case</span> FEASIBILITY:</div>
<div class="line"><a name="l00742"></a><span class="lineno"> 742</span>  <span class="comment">// Test if a connection point was found during tree expansion</span></div>
<div class="line"><a name="l00743"></a><span class="lineno"> 743</span>  <span class="keywordflow">return</span> (connection_point != <span class="keyword">nullptr</span> || ptc);</div>
<div class="line"><a name="l00744"></a><span class="lineno"> 744</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00745"></a><span class="lineno"> 745</span>  </div>
<div class="line"><a name="l00746"></a><span class="lineno"> 746</span>  <span class="keywordflow">case</span> OPTIMALITY:</div>
<div class="line"><a name="l00747"></a><span class="lineno"> 747</span>  <span class="comment">// Test if z is in SET_CLOSED (interior) of other tree</span></div>
<div class="line"><a name="l00748"></a><span class="lineno"> 748</span>  <span class="keywordflow">if</span> (ptc)</div>
<div class="line"><a name="l00749"></a><span class="lineno"> 749</span>  terminate = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00750"></a><span class="lineno"> 750</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (z-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#aa3bd634a6ef37e1c8a29d484420a6ccb">getOtherSet</a>() == BiDirMotion::SET_CLOSED)</div>
<div class="line"><a name="l00751"></a><span class="lineno"> 751</span>  terminate = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00752"></a><span class="lineno"> 752</span>  </div>
<div class="line"><a name="l00753"></a><span class="lineno"> 753</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00754"></a><span class="lineno"> 754</span>  };</div>
<div class="line"><a name="l00755"></a><span class="lineno"> 755</span>  <span class="keywordflow">return</span> terminate;</div>
<div class="line"><a name="l00756"></a><span class="lineno"> 756</span>  }</div>
<div class="line"><a name="l00757"></a><span class="lineno"> 757</span>  </div>
<div class="line"><a name="l00758"></a><span class="lineno"> 758</span>  <span class="comment">// Choose exploration tree and node z to expand</span></div>
<div class="line"><a name="l00759"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#aa6b17f4cbf54e75d8c7592f66a9d4b24"> 759</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#aa6b17f4cbf54e75d8c7592f66a9d4b24">BFMT::chooseTreeAndExpansionNode</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *&z)</div>
<div class="line"><a name="l00760"></a><span class="lineno"> 760</span>  {</div>
<div class="line"><a name="l00761"></a><span class="lineno"> 761</span>  <span class="keywordflow">switch</span> (exploration_)</div>
<div class="line"><a name="l00762"></a><span class="lineno"> 762</span>  {</div>
<div class="line"><a name="l00763"></a><span class="lineno"> 763</span>  <span class="keywordflow">case</span> SWAP_EVERY_TIME:</div>
<div class="line"><a name="l00764"></a><span class="lineno"> 764</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].empty())</div>
<div class="line"><a name="l00765"></a><span class="lineno"> 765</span>  z = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a5d1ecb7a7d154ad44df98a5109738697">top</a>()->data; <span class="comment">// Continue expanding the current tree (not empty by exit</span></div>
<div class="line"><a name="l00766"></a><span class="lineno"> 766</span>  <span class="comment">// condition in plan())</span></div>
<div class="line"><a name="l00767"></a><span class="lineno"> 767</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00768"></a><span class="lineno"> 768</span>  {</div>
<div class="line"><a name="l00769"></a><span class="lineno"> 769</span>  z = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].top()->data; <span class="comment">// Take top of opposite tree heap as new z</span></div>
<div class="line"><a name="l00770"></a><span class="lineno"> 770</span>  swapTrees(); <span class="comment">// Swap to the opposite tree</span></div>
<div class="line"><a name="l00771"></a><span class="lineno"> 771</span>  }</div>
<div class="line"><a name="l00772"></a><span class="lineno"> 772</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00773"></a><span class="lineno"> 773</span>  </div>
<div class="line"><a name="l00774"></a><span class="lineno"> 774</span>  <span class="keywordflow">case</span> CHOOSE_SMALLEST_Z:</div>
<div class="line"><a name="l00775"></a><span class="lineno"> 775</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *z1, *z2;</div>
<div class="line"><a name="l00776"></a><span class="lineno"> 776</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].empty())</div>
<div class="line"><a name="l00777"></a><span class="lineno"> 777</span>  z = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a5d1ecb7a7d154ad44df98a5109738697">top</a>()->data; <span class="comment">// Continue expanding the current tree (not empty by exit</span></div>
<div class="line"><a name="l00778"></a><span class="lineno"> 778</span>  <span class="comment">// condition in plan())</span></div>
<div class="line"><a name="l00779"></a><span class="lineno"> 779</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].empty())</div>
<div class="line"><a name="l00780"></a><span class="lineno"> 780</span>  {</div>
<div class="line"><a name="l00781"></a><span class="lineno"> 781</span>  z = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].top()->data; <span class="comment">// Take top of opposite tree heap as new z</span></div>
<div class="line"><a name="l00782"></a><span class="lineno"> 782</span>  swapTrees(); <span class="comment">// Swap to the opposite tree</span></div>
<div class="line"><a name="l00783"></a><span class="lineno"> 783</span>  }</div>
<div class="line"><a name="l00784"></a><span class="lineno"> 784</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00785"></a><span class="lineno"> 785</span>  {</div>
<div class="line"><a name="l00786"></a><span class="lineno"> 786</span>  z1 = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[tree_].<a class="code" href="classompl_1_1BinaryHeap.html#a5d1ecb7a7d154ad44df98a5109738697">top</a>()->data;</div>
<div class="line"><a name="l00787"></a><span class="lineno"> 787</span>  z2 = <a class="code" href="classompl_1_1geometric_1_1FMT.html#aca5af8c2d2b2a977c24a5077e386e39d">Open_</a>[(tree_ + 1) % 2].top()->data;</div>
<div class="line"><a name="l00788"></a><span class="lineno"> 788</span>  </div>
<div class="line"><a name="l00789"></a><span class="lineno"> 789</span>  <span class="keywordflow">if</span> (z1-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#aea2f60e9b2e74bc178a0c821f49498c9">getCost</a>().<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() < z2-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#acff919ffdcfa74546cd1fb4c3acf8270">getOtherCost</a>().<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>())</div>
<div class="line"><a name="l00790"></a><span class="lineno"> 790</span>  z = z1;</div>
<div class="line"><a name="l00791"></a><span class="lineno"> 791</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00792"></a><span class="lineno"> 792</span>  {</div>
<div class="line"><a name="l00793"></a><span class="lineno"> 793</span>  z = z2;</div>
<div class="line"><a name="l00794"></a><span class="lineno"> 794</span>  swapTrees();</div>
<div class="line"><a name="l00795"></a><span class="lineno"> 795</span>  }</div>
<div class="line"><a name="l00796"></a><span class="lineno"> 796</span>  }</div>
<div class="line"><a name="l00797"></a><span class="lineno"> 797</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00798"></a><span class="lineno"> 798</span>  };</div>
<div class="line"><a name="l00799"></a><span class="lineno"> 799</span>  }</div>
<div class="line"><a name="l00800"></a><span class="lineno"> 800</span>  </div>
<div class="line"><a name="l00801"></a><span class="lineno"> 801</span>  <span class="comment">// Trace a path of nodes along a tree towards the root (forward or reverse)</span></div>
<div class="line"><a name="l00802"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#a2510965e21e83dc60adfbec5bd0775ec"> 802</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#a2510965e21e83dc60adfbec5bd0775ec">BFMT::tracePath</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *z, BiDirMotionPtrs &path)</div>
<div class="line"><a name="l00803"></a><span class="lineno"> 803</span>  {</div>
<div class="line"><a name="l00804"></a><span class="lineno"> 804</span>  <a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *solution = z;</div>
<div class="line"><a name="l00805"></a><span class="lineno"> 805</span>  </div>
<div class="line"><a name="l00806"></a><span class="lineno"> 806</span>  <span class="keywordflow">while</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00807"></a><span class="lineno"> 807</span>  {</div>
<div class="line"><a name="l00808"></a><span class="lineno"> 808</span>  path.push_back(solution);</div>
<div class="line"><a name="l00809"></a><span class="lineno"> 809</span>  solution = solution-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#aebad985f06405e213256745474a6d510">getParent</a>();</div>
<div class="line"><a name="l00810"></a><span class="lineno"> 810</span>  }</div>
<div class="line"><a name="l00811"></a><span class="lineno"> 811</span>  }</div>
<div class="line"><a name="l00812"></a><span class="lineno"> 812</span>  </div>
<div class="line"><a name="l00813"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#ad16dfb44a33d551bbdf66e0d86d80a06"> 813</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#ad16dfb44a33d551bbdf66e0d86d80a06">BFMT::swapTrees</a>()</div>
<div class="line"><a name="l00814"></a><span class="lineno"> 814</span>  {</div>
<div class="line"><a name="l00815"></a><span class="lineno"> 815</span>  tree_ = (<a class="code" href="classompl_1_1geometric_1_1BFMT.html#ae4c3b14dbf4ab6dcf32d7c3bcf8a6dbf">TreeType</a>)((((<span class="keywordtype">int</span>)tree_) + 1) % 2);</div>
<div class="line"><a name="l00816"></a><span class="lineno"> 816</span>  }</div>
<div class="line"><a name="l00817"></a><span class="lineno"> 817</span>  </div>
<div class="line"><a name="l00818"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BFMT.html#ab8604f3f006cfc9db14fb83b8c549aba"> 818</a></span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BFMT.html#ab8604f3f006cfc9db14fb83b8c549aba">BFMT::updateNeighborhood</a>(<a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html">BiDirMotion</a> *m, <span class="keyword">const</span> std::vector<BiDirMotion *> nbh)</div>
<div class="line"><a name="l00819"></a><span class="lineno"> 819</span>  {</div>
<div class="line"><a name="l00820"></a><span class="lineno"> 820</span>  <span class="comment">// Neighborhoods are only updated if the new motion is within bounds (k nearest or within r).</span></div>
<div class="line"><a name="l00821"></a><span class="lineno"> 821</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> i : nbh)</div>
<div class="line"><a name="l00822"></a><span class="lineno"> 822</span>  {</div>
<div class="line"><a name="l00823"></a><span class="lineno"> 823</span>  <span class="comment">// If CLOSED, that neighborhood won't be used again.</span></div>
<div class="line"><a name="l00824"></a><span class="lineno"> 824</span>  <span class="comment">// Else, if neighhboorhod already exists, we have to insert the node in</span></div>
<div class="line"><a name="l00825"></a><span class="lineno"> 825</span>  <span class="comment">// the corresponding place of the neighborhood of the neighbor of m.</span></div>
<div class="line"><a name="l00826"></a><span class="lineno"> 826</span>  <span class="keywordflow">if</span> (i->getCurrentSet() == BiDirMotion::SET_CLOSED)</div>
<div class="line"><a name="l00827"></a><span class="lineno"> 827</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00828"></a><span class="lineno"> 828</span>  </div>
<div class="line"><a name="l00829"></a><span class="lineno"> 829</span>  <span class="keyword">auto</span> it = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>.find(i);</div>
<div class="line"><a name="l00830"></a><span class="lineno"> 830</span>  <span class="keywordflow">if</span> (it != <a class="code" href="classompl_1_1geometric_1_1FMT.html#a97fe3a95349783e8c43f579a5934f487">neighborhoods_</a>.end())</div>
<div class="line"><a name="l00831"></a><span class="lineno"> 831</span>  {</div>
<div class="line"><a name="l00832"></a><span class="lineno"> 832</span>  <span class="keywordflow">if</span> (it->second.empty())</div>
<div class="line"><a name="l00833"></a><span class="lineno"> 833</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00834"></a><span class="lineno"> 834</span>  </div>
<div class="line"><a name="l00835"></a><span class="lineno"> 835</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> connCost = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(i->getState(), m-><a class="code" href="classompl_1_1geometric_1_1BFMT_1_1BiDirMotion.html#a496d5366758c9b5808b273d4cbd370fa">getState</a>());</div>
<div class="line"><a name="l00836"></a><span class="lineno"> 836</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> worstCost = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(it->second.back()->getState(), i->getState());</div>
<div class="line"><a name="l00837"></a><span class="lineno"> 837</span>  </div>
<div class="line"><a name="l00838"></a><span class="lineno"> 838</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->isCostBetterThan(worstCost, connCost))</div>
<div class="line"><a name="l00839"></a><span class="lineno"> 839</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00840"></a><span class="lineno"> 840</span>  </div>
<div class="line"><a name="l00841"></a><span class="lineno"> 841</span>  <span class="comment">// insert the neighbor in the vector in the correct order</span></div>
<div class="line"><a name="l00842"></a><span class="lineno"> 842</span>  std::vector<BiDirMotion *> &nbhToUpdate = it->second;</div>
<div class="line"><a name="l00843"></a><span class="lineno"> 843</span>  <span class="keywordflow">for</span> (std::size_t j = 0; j < nbhToUpdate.size(); ++j)</div>
<div class="line"><a name="l00844"></a><span class="lineno"> 844</span>  {</div>
<div class="line"><a name="l00845"></a><span class="lineno"> 845</span>  <span class="comment">// If connection to the new state is better than the current neighbor tested, insert.</span></div>
<div class="line"><a name="l00846"></a><span class="lineno"> 846</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> cost = <a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->motionCost(i->getState(), nbhToUpdate[j]->getState());</div>
<div class="line"><a name="l00847"></a><span class="lineno"> 847</span>  <span class="keywordflow">if</span> (<a class="code" href="classompl_1_1geometric_1_1FMT.html#a67cd18c51459d03b612fb3c8355a4b66">opt_</a>->isCostBetterThan(connCost, cost))</div>