-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathBITstar_8cpp_source.html
1646 lines (1644 loc) · 270 KB
/
BITstar_8cpp_source.html
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/informedtrees/src/BITstar.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_efc272713926b2de5ae7b55e29402045.html">informedtrees</a></li><li class="navelem"><a class="el" href="dir_0a885573d7329905c5551dfa52f41624.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">BITstar.cpp</div> </div>
</div><!--header-->
<div class="contents">
<div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span> <span class="comment">/*********************************************************************</span></div>
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="comment"> * Software License Agreement (BSD License)</span></div>
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="comment"> *</span></div>
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span> <span class="comment"> * Copyright (c) 2014, University of Toronto</span></div>
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> <span class="comment"> * All rights reserved.</span></div>
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span> <span class="comment"> *</span></div>
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="comment"> * Redistribution and use in source and binary forms, with or without</span></div>
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span> <span class="comment"> * modification, are permitted provided that the following conditions</span></div>
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="comment"> * are met:</span></div>
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span> <span class="comment"> *</span></div>
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span> <span class="comment"> * * Redistributions of source code must retain the above copyright</span></div>
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="comment"> * notice, this list of conditions and the following disclaimer.</span></div>
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span> <span class="comment"> * * Redistributions in binary form must reproduce the above</span></div>
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span> <span class="comment"> * copyright notice, this list of conditions and the following</span></div>
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> <span class="comment"> * disclaimer in the documentation and/or other materials provided</span></div>
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span> <span class="comment"> * with the distribution.</span></div>
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span> <span class="comment"> * * Neither the name of the University of Toronto nor the names of its</span></div>
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span> <span class="comment"> * contributors may be used to endorse or promote products derived</span></div>
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span> <span class="comment"> * from this software without specific prior written permission.</span></div>
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span> <span class="comment"> *</span></div>
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span> <span class="comment"> * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span></div>
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span> <span class="comment"> * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span></div>
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span> <span class="comment"> * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span></div>
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span> <span class="comment"> * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span></div>
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span> <span class="comment"> * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span></div>
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span> <span class="comment"> * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span></div>
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span> <span class="comment"> * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span></div>
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span> <span class="comment"> * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span></div>
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span> <span class="comment"> * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span></div>
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span> <span class="comment"> * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span></div>
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span> <span class="comment"> * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span></div>
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span> <span class="comment"> * POSSIBILITY OF SUCH DAMAGE.</span></div>
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span> <span class="comment"> *********************************************************************/</span></div>
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span>  </div>
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span> <span class="comment">/* Authors: Jonathan Gammell, Marlin Strub */</span></div>
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span>  </div>
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/BITstar.h"</span></div>
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span>  </div>
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="preprocessor">#include <sstream></span></div>
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span> <span class="preprocessor">#include <iomanip></span></div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span> <span class="preprocessor">#include <memory></span></div>
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> <span class="preprocessor">#include <boost/range/adaptor/reversed.hpp></span></div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span>  </div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span> <span class="preprocessor">#include "<a class="code" href="Console_8h.html">ompl/util/Console.h</a>"</span></div>
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span> <span class="preprocessor">#include "ompl/util/Exception.h"</span></div>
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span> <span class="preprocessor">#include "ompl/util/String.h"</span></div>
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span> <span class="preprocessor">#include "ompl/geometric/PathGeometric.h"</span></div>
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span> <span class="preprocessor">#include "ompl/base/objectives/PathLengthOptimizationObjective.h"</span></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="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/HelperFunctions.h"</span></div>
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/IdGenerator.h"</span></div>
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/Vertex.h"</span></div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/CostHelper.h"</span></div>
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/ImplicitGraph.h"</span></div>
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span> <span class="preprocessor">#include "ompl/geometric/planners/informedtrees/bitstar/SearchQueue.h"</span></div>
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span>  </div>
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span> <span class="preprocessor">#warning Compiling BIT* with debug-level asserts.</span></div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span> <span class="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  </div>
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span> <span class="keyword">namespace </span><a class="code" href="namespaceompl.html">ompl</a></div>
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span> {</div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  <span class="keyword">namespace </span>geometric</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_1BITstar.html#aa0dc941b1746d8a412a81561296e8bdf">BITstar::BITstar</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1SpaceInformationPtr.html">ompl::base::SpaceInformationPtr</a> &si, <span class="keyword">const</span> std::string &name <span class="comment">/*= "BITstar"*/</span>)</div>
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span>  : <a class="code" href="namespaceompl.html">ompl</a>::base::Planner(si, name)</div>
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  {</div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"%s: Compiled with debug-level asserts."</span>, Planner::getName().c_str());</div>
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span> <span class="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span>  </div>
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span>  <span class="comment">// Allocate my helper classes, they hold settings and must never be deallocated. Give them a pointer to my</span></div>
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  <span class="comment">// name, so they can output helpful error messages</span></div>
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span>  costHelpPtr_ = std::make_shared<CostHelper>();</div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  graphPtr_ = std::make_shared<ImplicitGraph>([<span class="keyword">this</span>]() { <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>(); });</div>
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span>  queuePtr_ = std::make_shared<SearchQueue>([<span class="keyword">this</span>]() { <span class="keywordflow">return</span> <a class="code" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>(); });</div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  </div>
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  <span class="comment">// Specify my planner specs:</span></div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  Planner::specs_.recognizedGoal = <a class="code" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55a6fb685fa51055688c4e130094225b7f9">ompl::base::GOAL_SAMPLEABLE_REGION</a>;</div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  Planner::specs_.multithreaded = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  <span class="comment">// Approximate solutions are supported but must be enabled with the appropriate configuration parameter.</span></div>
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  Planner::specs_.approximateSolutions = graphPtr_->getTrackApproximateSolutions();</div>
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  Planner::specs_.optimizingPaths = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  Planner::specs_.directed = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  Planner::specs_.provingSolutionNonExistence = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span>  Planner::specs_.canReportIntermediateSolutions = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  </div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  <span class="comment">// Register my setting callbacks</span></div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  Planner::declareParam<double>(<span class="stringliteral">"rewire_factor"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a36d6bfe6fc9972debf35a8798c082ba5">BITstar::setRewireFactor</a>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a2953c826f125b14806507df841744308">BITstar::getRewireFactor</a>,</div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  <span class="stringliteral">"1.0:0.01:3.0"</span>);</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  Planner::declareParam<unsigned int>(<span class="stringliteral">"samples_per_batch"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a8b513410d75af41e532aabe486f3d962">BITstar::setSamplesPerBatch</a>,</div>
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a38da6dd6e65573fd9c69ffc939fcff87">BITstar::getSamplesPerBatch</a>, <span class="stringliteral">"1:1:1000000"</span>);</div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  Planner::declareParam<bool>(<span class="stringliteral">"use_k_nearest"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#abd4379f27e55f1ef5b6026bf772316fb">BITstar::setUseKNearest</a>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#aefcfb0e16ffcec9e041e26531fd32779">BITstar::getUseKNearest</a>,</div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  <span class="stringliteral">"0,"</span></div>
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span>  <span class="stringliteral">"1"</span>);</div>
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  Planner::declareParam<bool>(<span class="stringliteral">"use_graph_pruning"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a742fde56a552462b86ec5ae593141c2a">BITstar::setPruning</a>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a06418ecfcc2236f7a42503799bed739b">BITstar::getPruning</a>,</div>
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  <span class="stringliteral">"0,"</span></div>
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  <span class="stringliteral">"1"</span>);</div>
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  Planner::declareParam<double>(<span class="stringliteral">"prune_threshold_as_fractional_cost_change"</span>, <span class="keyword">this</span>,</div>
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#ab7a52698a1d43a1858aec85dd21cabb9">BITstar::setPruneThresholdFraction</a>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a23c1d41b65142f1cab9959db46e00123">BITstar::getPruneThresholdFraction</a>,</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <span class="stringliteral">"0.0:0.01:1.0"</span>);</div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  Planner::declareParam<bool>(<span class="stringliteral">"delay_rewiring_to_first_solution"</span>, <span class="keyword">this</span>,</div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#ae4ecec0085a6485ffd5c67857d478e42">BITstar::setDelayRewiringUntilInitialSolution</a>,</div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#aaac2dc73ed23702525583ef8f351d3f9">BITstar::getDelayRewiringUntilInitialSolution</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  Planner::declareParam<bool>(<span class="stringliteral">"use_just_in_time_sampling"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a9e6ed621c5da68d0bda40195e5c31c78">BITstar::setJustInTimeSampling</a>,</div>
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a4d920a907409d94337c1cfc62a5e4476">BITstar::getJustInTimeSampling</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  Planner::declareParam<bool>(<span class="stringliteral">"drop_unconnected_samples_on_prune"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a1f801a1305705a067da449fa92699d99">BITstar::setDropSamplesOnPrune</a>,</div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#af1773a4902d58b78216ae1b5a73700dd">BITstar::getDropSamplesOnPrune</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  Planner::declareParam<bool>(<span class="stringliteral">"stop_on_each_solution_improvement"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a1ddab1a9472e527a010615dbf107d7b0">BITstar::setStopOnSolnImprovement</a>,</div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a797f779fb9aec4ec1460f28d65faae81">BITstar::getStopOnSolnImprovement</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  Planner::declareParam<bool>(<span class="stringliteral">"use_strict_queue_ordering"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a4c6ed74080a858a36e2bca01eed93073">BITstar::setStrictQueueOrdering</a>,</div>
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#a210174d16947876725c5a902da1fb203">BITstar::getStrictQueueOrdering</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  Planner::declareParam<bool>(<span class="stringliteral">"find_approximate_solutions"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#ac18d340b00758c7089630e137697c8a2">BITstar::setConsiderApproximateSolutions</a>,</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  &<a class="code" href="classompl_1_1geometric_1_1BITstar.html#ac5b006832ccf3da674408199809b3804">BITstar::getConsiderApproximateSolutions</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00115"></a><span class="lineno"> 115</span>  </div>
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span>  <span class="comment">// Register my progress info:</span></div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a3dc481539fac465497ad158e1bdac91a">addPlannerProgressProperty</a>(<span class="stringliteral">"best cost DOUBLE"</span>, [<span class="keyword">this</span>] { <span class="keywordflow">return</span> bestCostProgressProperty(); });</div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a3dc481539fac465497ad158e1bdac91a">addPlannerProgressProperty</a>(<span class="stringliteral">"number of segments in solution path INTEGER"</span>,</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  [<span class="keyword">this</span>] { <span class="keywordflow">return</span> bestLengthProgressProperty(); });</div>
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a3dc481539fac465497ad158e1bdac91a">addPlannerProgressProperty</a>(<span class="stringliteral">"state collision checks INTEGER"</span>,</div>
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span>  [<span class="keyword">this</span>] { <span class="keywordflow">return</span> stateCollisionCheckProgressProperty(); });</div>
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a3dc481539fac465497ad158e1bdac91a">addPlannerProgressProperty</a>(<span class="stringliteral">"edge collision checks INTEGER"</span>,</div>
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span>  [<span class="keyword">this</span>] { <span class="keywordflow">return</span> edgeCollisionCheckProgressProperty(); });</div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a3dc481539fac465497ad158e1bdac91a">addPlannerProgressProperty</a>(<span class="stringliteral">"nearest neighbour calls INTEGER"</span>,</div>
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span>  [<span class="keyword">this</span>] { <span class="keywordflow">return</span> nearestNeighbourProgressProperty(); });</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="comment">// Extra progress info that aren't necessary for every day use. Uncomment if desired.</span></div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="comment">/*</span></div>
<div class="line"><a name="l00129"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#aa0dc941b1746d8a412a81561296e8bdf"> 129</a></span> <span class="comment"> addPlannerProgressProperty("edge queue size INTEGER", [this]</span></div>
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00131"></a><span class="lineno"> 131</span> <span class="comment"> return edgeQueueSizeProgressProperty();</span></div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span> <span class="comment"> addPlannerProgressProperty("iterations INTEGER", [this]</span></div>
<div class="line"><a name="l00134"></a><span class="lineno"> 134</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span> <span class="comment"> return iterationProgressProperty();</span></div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span> <span class="comment"> addPlannerProgressProperty("batches INTEGER", [this]</span></div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span> <span class="comment"> return batchesProgressProperty();</span></div>
<div class="line"><a name="l00140"></a><span class="lineno"> 140</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span> <span class="comment"> addPlannerProgressProperty("graph prunings INTEGER", [this]</span></div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span> <span class="comment"> return pruningProgressProperty();</span></div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span> <span class="comment"> addPlannerProgressProperty("total states generated INTEGER", [this]</span></div>
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span> <span class="comment"> return totalStatesCreatedProgressProperty();</span></div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span> <span class="comment"> addPlannerProgressProperty("vertices constructed INTEGER", [this]</span></div>
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span> <span class="comment"> return verticesConstructedProgressProperty();</span></div>
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span> <span class="comment"> addPlannerProgressProperty("states pruned INTEGER", [this]</span></div>
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span> <span class="comment"> return statesPrunedProgressProperty();</span></div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00157"></a><span class="lineno"> 157</span> <span class="comment"> addPlannerProgressProperty("graph vertices disconnected INTEGER", [this]</span></div>
<div class="line"><a name="l00158"></a><span class="lineno"> 158</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span> <span class="comment"> return verticesDisconnectedProgressProperty();</span></div>
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span> <span class="comment"> addPlannerProgressProperty("rewiring edges INTEGER", [this]</span></div>
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span> <span class="comment"> {</span></div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span> <span class="comment"> return rewiringProgressProperty();</span></div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span> <span class="comment"> });</span></div>
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span> <span class="comment"> */</span></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>  </div>
<div class="line"><a name="l00168"></a><span class="lineno"> 168</span>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#aa2da7cea603e0dc641a45ad353ff522e">BITstar::setup</a>()</div>
<div class="line"><a name="l00169"></a><span class="lineno"> 169</span>  {</div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  <span class="comment">// Call the base class setup. Marks Planner::setup_ as true.</span></div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  Planner::setup();</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="comment">// Check if we have a problem definition</span></div>
<div class="line"><a name="l00174"></a><span class="lineno"> 174</span>  <span class="keywordflow">if</span> (<span class="keyword">static_cast<</span><span class="keywordtype">bool</span><span class="keyword">></span>(Planner::pdef_))</div>
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  {</div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  <span class="comment">// We do, do some initialization work.</span></div>
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  <span class="comment">// See if we have an optimization objective</span></div>
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  <span class="keywordflow">if</span> (!Planner::pdef_->hasOptimizationObjective())</div>
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  {</div>
<div class="line"><a name="l00180"></a><span class="lineno"> 180</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="l00181"></a><span class="lineno"> 181</span>  Planner::getName().c_str());</div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  Planner::pdef_->setOptimizationObjective(</div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span>  std::make_shared<base::PathLengthOptimizationObjective>(Planner::si_));</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>  <span class="comment">// No else, we were given one.</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"> 187</span>  <span class="comment">// Initialize the best cost found so far to be infinite.</span></div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  bestCost_ = Planner::pdef_->getOptimizationObjective()->infiniteCost();</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="comment">// If the problem definition *has* a goal, make sure it is of appropriate type</span></div>
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  <span class="keywordflow">if</span> (<span class="keyword">static_cast<</span><span class="keywordtype">bool</span><span class="keyword">></span>(Planner::pdef_->getGoal()))</div>
<div class="line"><a name="l00192"></a><span class="lineno"> 192</span>  {</div>
<div class="line"><a name="l00193"></a><span class="lineno"> 193</span>  <span class="keywordflow">if</span> (!Planner::pdef_->getGoal()->hasType(<a class="code" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55a6fb685fa51055688c4e130094225b7f9">ompl::base::GOAL_SAMPLEABLE_REGION</a>))</div>
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  {</div>
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s::setup() BIT* currently only supports goals that can be cast to a sampleable "</span></div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  <span class="stringliteral">"goal region."</span>,</div>
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  Planner::getName().c_str());</div>
<div class="line"><a name="l00198"></a><span class="lineno"> 198</span>  <span class="comment">// Mark as not setup:</span></div>
<div class="line"><a name="l00199"></a><span class="lineno"> 199</span>  Planner::setup_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span>  <span class="keywordflow">return</span>;</div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  }</div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  <span class="comment">// No else, of correct type.</span></div>
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  }</div>
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  <span class="comment">// No else, called without a goal. Is this MoveIt?</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>  <span class="comment">// Setup the CostHelper, it provides everything I need from optimization objective plus some frills</span></div>
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  costHelpPtr_->setup(Planner::pdef_->getOptimizationObjective(), graphPtr_.get());</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">// Setup the queue</span></div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  queuePtr_->setup(costHelpPtr_.get(), graphPtr_.get());</div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  </div>
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  <span class="comment">// Setup the graph, it does not hold a copy of this or Planner::pis_, but uses them to create a NN</span></div>
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  <span class="comment">// struct and check for starts/goals, respectively.</span></div>
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  graphPtr_->setup(Planner::si_, Planner::pdef_, costHelpPtr_.get(), queuePtr_.get(), <span class="keyword">this</span>,</div>
<div class="line"><a name="l00215"></a><span class="lineno"> 215</span>  Planner::pis_);</div>
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span>  graphPtr_->setPruning(isPruningEnabled_);</div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  </div>
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span>  <span class="comment">// Set the best and pruned costs to the proper objective-based values:</span></div>
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span>  bestCost_ = costHelpPtr_->infiniteCost();</div>
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span>  prunedCost_ = costHelpPtr_->infiniteCost();</div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span>  </div>
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span>  <span class="comment">// Get the measure of the problem</span></div>
<div class="line"><a name="l00223"></a><span class="lineno"> 223</span>  prunedMeasure_ = Planner::si_->getSpaceMeasure();</div>
<div class="line"><a name="l00224"></a><span class="lineno"> 224</span>  </div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  <span class="comment">// If the planner is default named, we change it:</span></div>
<div class="line"><a name="l00226"></a><span class="lineno"> 226</span>  <span class="keywordflow">if</span> (!graphPtr_->getUseKNearest() && Planner::getName() == <span class="stringliteral">"kBITstar"</span>)</div>
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span>  {</div>
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  <span class="comment">// It's current the default k-nearest BIT* name, and we're toggling, so set to the default r-disc</span></div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"BIT*: An r-disc version of BIT* can not be named 'kBITstar', as this name is reserved "</span></div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span>  <span class="stringliteral">"for the k-nearest version. Changing the name to 'BITstar'."</span>);</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  Planner::setName(<span class="stringliteral">"BITstar"</span>);</div>
<div class="line"><a name="l00232"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#aa2da7cea603e0dc641a45ad353ff522e"> 232</a></span>  }</div>
<div class="line"><a name="l00233"></a><span class="lineno"> 233</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (graphPtr_->getUseKNearest() && Planner::getName() == <span class="stringliteral">"BITstar"</span>)</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>  <span class="comment">// It's current the default r-disc BIT* name, and we're toggling, so set to the default k-nearest</span></div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"BIT*: A k-nearest version of BIT* can not be named 'BITstar', as this name is reserved "</span></div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  <span class="stringliteral">"for the r-disc version. Changing the name to 'kBITstar'."</span>);</div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  Planner::setName(<span class="stringliteral">"kBITstar"</span>);</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>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (!graphPtr_->getUseKNearest() && Planner::getName() == <span class="stringliteral">"kABITstar"</span>)</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>  <span class="comment">// It's current the default k-nearest ABIT* name, and we're toggling, so set to the default r-disc</span></div>
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"ABIT*: An r-disc version of ABIT* can not be named 'kABITstar', as this name is "</span></div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  <span class="stringliteral">"reserved for the k-nearest version. Changing the name to 'ABITstar'."</span>);</div>
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  Planner::setName(<span class="stringliteral">"ABITstar"</span>);</div>
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  }</div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (graphPtr_->getUseKNearest() && Planner::getName() == <span class="stringliteral">"ABITstar"</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>  <span class="comment">// It's current the default r-disc ABIT* name, and we're toggling, so set to the default k-nearest</span></div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"ABIT*: A k-nearest version of ABIT* can not be named 'ABITstar', as this name is "</span></div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  <span class="stringliteral">"reserved for the r-disc version. Changing the name to 'kABITstar'."</span>);</div>
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span>  Planner::setName(<span class="stringliteral">"kABITstar"</span>);</div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span>  }</div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  <span class="comment">// It's not default named, don't change it</span></div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  }</div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span>  {</div>
<div class="line"><a name="l00258"></a><span class="lineno"> 258</span>  <span class="comment">// We don't, so we can't setup. Make sure that is explicit.</span></div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  Planner::setup_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span>  }</div>
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  }</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>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#aa028529f177f630c61bacaf3f80c966a">BITstar::clear</a>()</div>
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  {</div>
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  <span class="comment">// Clear all the variables.</span></div>
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  <span class="comment">// Keep this in the order of the constructors:</span></div>
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span>  </div>
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span>  <span class="comment">// The various helper classes. DO NOT reset the pointers, they hold configuration parameters:</span></div>
<div class="line"><a name="l00269"></a><span class="lineno"> 269</span>  costHelpPtr_->reset();</div>
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span>  graphPtr_->reset();</div>
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span>  queuePtr_->reset();</div>
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span>  </div>
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span>  <span class="comment">// Reset the various calculations and convenience containers. Will be recalculated on setup</span></div>
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span>  curGoalVertex_.reset();</div>
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span>  bestCost_ = <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a>(std::numeric_limits<double>::infinity());</div>
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  bestLength_ = 0u;</div>
<div class="line"><a name="l00277"></a><span class="lineno"> 277</span>  prunedCost_ = <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a>(std::numeric_limits<double>::infinity());</div>
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span>  prunedMeasure_ = 0.0;</div>
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  hasExactSolution_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  stopLoop_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  numBatches_ = 0u;</div>
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  numPrunings_ = 0u;</div>
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  numIterations_ = 0u;</div>
<div class="line"><a name="l00284"></a><span class="lineno"> 284</span>  numEdgeCollisionChecks_ = 0u;</div>
<div class="line"><a name="l00285"></a><span class="lineno"> 285</span>  numRewirings_ = 0u;</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">// DO NOT reset the configuration parameters:</span></div>
<div class="line"><a name="l00288"></a><span class="lineno"> 288</span>  <span class="comment">// samplesPerBatch_</span></div>
<div class="line"><a name="l00289"></a><span class="lineno"> 289</span>  <span class="comment">// usePruning_</span></div>
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span>  <span class="comment">// pruneFraction_</span></div>
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  <span class="comment">// stopOnSolnChange_</span></div>
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span>  </div>
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  <span class="comment">// Mark as not setup:</span></div>
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span>  Planner::setup_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span>  </div>
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span>  <span class="comment">// Call my base clear:</span></div>
<div class="line"><a name="l00297"></a><span class="lineno"> 297</span>  Planner::clear();</div>
<div class="line"><a name="l00298"></a><span class="lineno"> 298</span>  }</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>  <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#ac830346ee0fe7e8cc475d715e2990b40">BITstar::solve</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span>  {</div>
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span>  <span class="comment">// Check that Planner::setup_ is true, if not call this->setup()</span></div>
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span>  Planner::checkValidity();</div>
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span>  </div>
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span>  <span class="comment">// Assert setup succeeded</span></div>
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span>  <span class="keywordflow">if</span> (!Planner::setup_)</div>
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span>  {</div>
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"%s::solve() failed to set up the planner. Has a problem definition been set?"</span>,</div>
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span>  Planner::getName().c_str());</div>
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span>  }</div>
<div class="line"><a name="l00311"></a><span class="lineno"> 311</span>  <span class="comment">// No else</span></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>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Searching for a solution to the given planning problem."</span>, Planner::getName().c_str());</div>
<div class="line"><a name="l00314"></a><span class="lineno"> 314</span>  </div>
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span>  <span class="comment">// Reset the manual stop to the iteration loop:</span></div>
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span>  stopLoop_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span>  </div>
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span>  <span class="comment">// If we don't have a goal yet, recall updateStartAndGoalStates, but wait for the first goal (or until the</span></div>
<div class="line"><a name="l00319"></a><span class="lineno"> 319</span>  <span class="comment">// PTC comes true and we give up):</span></div>
<div class="line"><a name="l00320"></a><span class="lineno"> 320</span>  <span class="keywordflow">if</span> (!graphPtr_->hasAGoal())</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>  graphPtr_->updateStartAndGoalStates(Planner::pis_, ptc);</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>  </div>
<div class="line"><a name="l00325"></a><span class="lineno"> 325</span>  <span class="comment">// Warn if we are missing a start</span></div>
<div class="line"><a name="l00326"></a><span class="lineno"> 326</span>  <span class="keywordflow">if</span> (!graphPtr_->hasAStart())</div>
<div class="line"><a name="l00327"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#aa028529f177f630c61bacaf3f80c966a"> 327</a></span>  {</div>
<div class="line"><a name="l00328"></a><span class="lineno"> 328</span>  <span class="comment">// We don't have a start, since there's no way to wait for one to appear, so we will not be solving this</span></div>
<div class="line"><a name="l00329"></a><span class="lineno"> 329</span>  <span class="comment">// "problem" today</span></div>
<div class="line"><a name="l00330"></a><span class="lineno"> 330</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"%s: A solution cannot be found as no valid start states are available."</span>,</div>
<div class="line"><a name="l00331"></a><span class="lineno"> 331</span>  Planner::getName().c_str());</div>
<div class="line"><a name="l00332"></a><span class="lineno"> 332</span>  }</div>
<div class="line"><a name="l00333"></a><span class="lineno"> 333</span>  <span class="comment">// No else, it's a start</span></div>
<div class="line"><a name="l00334"></a><span class="lineno"> 334</span>  </div>
<div class="line"><a name="l00335"></a><span class="lineno"> 335</span>  <span class="comment">// Warn if we are missing a goal</span></div>
<div class="line"><a name="l00336"></a><span class="lineno"> 336</span>  <span class="keywordflow">if</span> (!graphPtr_->hasAGoal())</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="comment">// We don't have a goal (and we waited as long as ptc allowed us for one to appear), so we will not be</span></div>
<div class="line"><a name="l00339"></a><span class="lineno"> 339</span>  <span class="comment">// solving this "problem" today</span></div>
<div class="line"><a name="l00340"></a><span class="lineno"> 340</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"%s: A solution cannot be found as no valid goal states are available."</span>,</div>
<div class="line"><a name="l00341"></a><span class="lineno"> 341</span>  Planner::getName().c_str());</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="comment">// No else, there's a goal to all of this</span></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="comment">// Insert the outgoing edges of the start vertices.</span></div>
<div class="line"><a name="l00346"></a><span class="lineno"> 346</span>  <span class="keywordflow">if</span> (numIterations_ == 0u)</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>  queuePtr_->insertOutgoingEdgesOfStartVertices();</div>
<div class="line"><a name="l00349"></a><span class="lineno"> 349</span>  }</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>  <span class="comment">/* Iterate as long as:</span></div>
<div class="line"><a name="l00352"></a><span class="lineno"> 352</span> <span class="comment"> - We're allowed (ptc == false && stopLoop_ == false), AND</span></div>
<div class="line"><a name="l00353"></a><span class="lineno"> 353</span> <span class="comment"> - We haven't found a good enough solution (costHelpPtr_->isSatisfied(bestCost) == false),</span></div>
<div class="line"><a name="l00354"></a><span class="lineno"> 354</span> <span class="comment"> - AND</span></div>
<div class="line"><a name="l00355"></a><span class="lineno"> 355</span> <span class="comment"> - There is a theoretically better solution (costHelpPtr_->isCostBetterThan(graphPtr_->minCost(),</span></div>
<div class="line"><a name="l00356"></a><span class="lineno"> 356</span> <span class="comment"> bestCost_) == true), OR</span></div>
<div class="line"><a name="l00357"></a><span class="lineno"> 357</span> <span class="comment"> - There is are start/goal states we've yet to consider (pis_.haveMoreStartStates() == true ||</span></div>
<div class="line"><a name="l00358"></a><span class="lineno"> 358</span> <span class="comment"> pis_.haveMoreGoalStates() == true)</span></div>
<div class="line"><a name="l00359"></a><span class="lineno"> 359</span> <span class="comment"> */</span></div>
<div class="line"><a name="l00360"></a><span class="lineno"> 360</span>  <span class="keywordflow">while</span> (!ptc && !stopLoop_ && !costHelpPtr_->isSatisfied(bestCost_) &&</div>
<div class="line"><a name="l00361"></a><span class="lineno"> 361</span>  (costHelpPtr_->isCostBetterThan(graphPtr_->minCost(), bestCost_) ||</div>
<div class="line"><a name="l00362"></a><span class="lineno"> 362</span>  Planner::pis_.haveMoreStartStates() || Planner::pis_.haveMoreGoalStates()))</div>
<div class="line"><a name="l00363"></a><span class="lineno"> 363</span>  {</div>
<div class="line"><a name="l00364"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#ac830346ee0fe7e8cc475d715e2990b40"> 364</a></span>  this->iterate();</div>
<div class="line"><a name="l00365"></a><span class="lineno"> 365</span>  }</div>
<div class="line"><a name="l00366"></a><span class="lineno"> 366</span>  </div>
<div class="line"><a name="l00367"></a><span class="lineno"> 367</span>  <span class="comment">// Announce</span></div>
<div class="line"><a name="l00368"></a><span class="lineno"> 368</span>  <span class="keywordflow">if</span> (hasExactSolution_)</div>
<div class="line"><a name="l00369"></a><span class="lineno"> 369</span>  {</div>
<div class="line"><a name="l00370"></a><span class="lineno"> 370</span>  this->endSuccessMessage();</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></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>  this->endFailureMessage();</div>
<div class="line"><a name="l00375"></a><span class="lineno"> 375</span>  }</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="comment">// Publish</span></div>
<div class="line"><a name="l00378"></a><span class="lineno"> 378</span>  <span class="keywordflow">if</span> (hasExactSolution_ || graphPtr_->getTrackApproximateSolutions())</div>
<div class="line"><a name="l00379"></a><span class="lineno"> 379</span>  {</div>
<div class="line"><a name="l00380"></a><span class="lineno"> 380</span>  <span class="comment">// Any solution</span></div>
<div class="line"><a name="l00381"></a><span class="lineno"> 381</span>  this->publishSolution();</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">// No else, no solution to publish</span></div>
<div class="line"><a name="l00384"></a><span class="lineno"> 384</span>  </div>
<div class="line"><a name="l00385"></a><span class="lineno"> 385</span>  <span class="comment">// From OMPL's point-of-view, BIT* can always have an approximate solution, so mark solution true if either</span></div>
<div class="line"><a name="l00386"></a><span class="lineno"> 386</span>  <span class="comment">// we have an exact solution or are finding approximate ones.</span></div>
<div class="line"><a name="l00387"></a><span class="lineno"> 387</span>  <span class="comment">// Our returned solution will only be approximate if it is not exact and we are finding approximate</span></div>
<div class="line"><a name="l00388"></a><span class="lineno"> 388</span>  <span class="comment">// solutions.</span></div>
<div class="line"><a name="l00389"></a><span class="lineno"> 389</span>  <span class="comment">// PlannerStatus(addedSolution, approximate)</span></div>
<div class="line"><a name="l00390"></a><span class="lineno"> 390</span>  <span class="keywordflow">return</span> {hasExactSolution_ || graphPtr_->getTrackApproximateSolutions(),</div>
<div class="line"><a name="l00391"></a><span class="lineno"> 391</span>  !hasExactSolution_ && graphPtr_->getTrackApproximateSolutions()};</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>  <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a5f6f7f012a594c2294cda637395f93e9">BITstar::getPlannerData</a>(<a class="code" href="classompl_1_1base_1_1PlannerData.html">ompl::base::PlannerData</a> &data)<span class="keyword"> const</span></div>
<div class="line"><a name="l00395"></a><span class="lineno"> 395</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00396"></a><span class="lineno"> 396</span>  <span class="comment">// Get the base planner class data:</span></div>
<div class="line"><a name="l00397"></a><span class="lineno"> 397</span>  Planner::getPlannerData(data);</div>
<div class="line"><a name="l00398"></a><span class="lineno"> 398</span>  </div>
<div class="line"><a name="l00399"></a><span class="lineno"> 399</span>  <span class="comment">// Add the samples (the graph)</span></div>
<div class="line"><a name="l00400"></a><span class="lineno"> 400</span>  graphPtr_->getGraphAsPlannerData(data);</div>
<div class="line"><a name="l00401"></a><span class="lineno"> 401</span>  </div>
<div class="line"><a name="l00402"></a><span class="lineno"> 402</span>  <span class="comment">// Did we find a solution?</span></div>
<div class="line"><a name="l00403"></a><span class="lineno"> 403</span>  <span class="keywordflow">if</span> (hasExactSolution_)</div>
<div class="line"><a name="l00404"></a><span class="lineno"> 404</span>  {</div>
<div class="line"><a name="l00405"></a><span class="lineno"> 405</span>  <span class="comment">// Exact solution</span></div>
<div class="line"><a name="l00406"></a><span class="lineno"> 406</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a7772ac307d153831c0e7ecfc4fb1c18b">markGoalState</a>(curGoalVertex_->state());</div>
<div class="line"><a name="l00407"></a><span class="lineno"> 407</span>  }</div>
<div class="line"><a name="l00408"></a><span class="lineno"> 408</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (!hasExactSolution_ && graphPtr_->getTrackApproximateSolutions())</div>
<div class="line"><a name="l00409"></a><span class="lineno"> 409</span>  {</div>
<div class="line"><a name="l00410"></a><span class="lineno"> 410</span>  <span class="comment">// Approximate solution</span></div>
<div class="line"><a name="l00411"></a><span class="lineno"> 411</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a7772ac307d153831c0e7ecfc4fb1c18b">markGoalState</a>(graphPtr_->closestVertexToGoal()->state());</div>
<div class="line"><a name="l00412"></a><span class="lineno"> 412</span>  }</div>
<div class="line"><a name="l00413"></a><span class="lineno"> 413</span>  <span class="comment">// No else, no solution</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>  </div>
<div class="line"><a name="l00416"></a><span class="lineno"> 416</span>  std::pair<ompl::base::State const *, ompl::base::State const *> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#af38417dd67de2b6cee9d1ee09e501c68">BITstar::getNextEdgeInQueue</a>()</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>  <span class="comment">// Variable:</span></div>
<div class="line"><a name="l00419"></a><span class="lineno"> 419</span>  <span class="comment">// The next edge as a basic pair of states</span></div>
<div class="line"><a name="l00420"></a><span class="lineno"> 420</span>  std::pair<ompl::base::State const *, ompl::base::State const *> nextEdge;</div>
<div class="line"><a name="l00421"></a><span class="lineno"> 421</span>  </div>
<div class="line"><a name="l00422"></a><span class="lineno"> 422</span>  <span class="keywordflow">if</span> (!queuePtr_->isEmpty())</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">// Variable</span></div>
<div class="line"><a name="l00425"></a><span class="lineno"> 425</span>  <span class="comment">// The edge in the front of the queue</span></div>
<div class="line"><a name="l00426"></a><span class="lineno"> 426</span>  <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a82784a5cbc1a9c9c81be04a4a4f478a5">VertexConstPtrPair</a> frontEdge = queuePtr_->getFrontEdge();</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="comment">// The next edge in the queue:</span></div>
<div class="line"><a name="l00429"></a><span class="lineno"> 429</span>  nextEdge = std::make_pair(frontEdge.first->state(), frontEdge.second->state());</div>
<div class="line"><a name="l00430"></a><span class="lineno"> 430</span>  }</div>
<div class="line"><a name="l00431"></a><span class="lineno"> 431</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00432"></a><span class="lineno"> 432</span>  {</div>
<div class="line"><a name="l00433"></a><span class="lineno"> 433</span>  <span class="comment">// An empty edge:</span></div>
<div class="line"><a name="l00434"></a><span class="lineno"> 434</span>  nextEdge = std::make_pair<ompl::base::State *, ompl::base::State *>(<span class="keyword">nullptr</span>, <span class="keyword">nullptr</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>  </div>
<div class="line"><a name="l00437"></a><span class="lineno"> 437</span>  <span class="keywordflow">return</span> nextEdge;</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>  </div>
<div class="line"><a name="l00440"></a><span class="lineno"> 440</span>  <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a9441e73fbec5789e481fbcee9c76d4b1">BITstar::getNextEdgeValueInQueue</a>()</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">// Variable</span></div>
<div class="line"><a name="l00443"></a><span class="lineno"> 443</span>  <span class="comment">// The cost of the next edge</span></div>
<div class="line"><a name="l00444"></a><span class="lineno"> 444</span>  <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> nextCost;</div>
<div class="line"><a name="l00445"></a><span class="lineno"> 445</span>  </div>
<div class="line"><a name="l00446"></a><span class="lineno"> 446</span>  <span class="keywordflow">if</span> (!queuePtr_->isEmpty())</div>
<div class="line"><a name="l00447"></a><span class="lineno"> 447</span>  {</div>
<div class="line"><a name="l00448"></a><span class="lineno"> 448</span>  <span class="comment">// The next cost in the queue:</span></div>
<div class="line"><a name="l00449"></a><span class="lineno"> 449</span>  nextCost = queuePtr_->getFrontEdgeValue().at(0u);</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>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00452"></a><span class="lineno"> 452</span>  {</div>
<div class="line"><a name="l00453"></a><span class="lineno"> 453</span>  <span class="comment">// An infinite cost:</span></div>
<div class="line"><a name="l00454"></a><span class="lineno"> 454</span>  nextCost = costHelpPtr_->infiniteCost();</div>
<div class="line"><a name="l00455"></a><span class="lineno"> 455</span>  }</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="keywordflow">return</span> nextCost;</div>
<div class="line"><a name="l00458"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#a5f6f7f012a594c2294cda637395f93e9"> 458</a></span>  }</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="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a13d6b414a6cf05d37e7c37d3931ccb38">BITstar::getEdgeQueue</a>(VertexConstPtrPairVector *edgesInQueue)</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>  queuePtr_->getEdges(edgesInQueue);</div>
<div class="line"><a name="l00463"></a><span class="lineno"> 463</span>  }</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>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a6849d38db6c966e12fbc2ae575acd98f">BITstar::numIterations</a>()<span class="keyword"> const</span></div>
<div class="line"><a name="l00466"></a><span class="lineno"> 466</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00467"></a><span class="lineno"> 467</span>  <span class="keywordflow">return</span> numIterations_;</div>
<div class="line"><a name="l00468"></a><span class="lineno"> 468</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>  <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a0b681699d607545e82b922138899e41e">BITstar::bestCost</a>()<span class="keyword"> const</span></div>
<div class="line"><a name="l00471"></a><span class="lineno"> 471</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00472"></a><span class="lineno"> 472</span>  <span class="keywordflow">return</span> bestCost_;</div>
<div class="line"><a name="l00473"></a><span class="lineno"> 473</span>  }</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>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1geometric_1_1BITstar.html#adbd5197b394d63359c072d3e1d6e9339">BITstar::numBatches</a>()<span class="keyword"> const</span></div>
<div class="line"><a name="l00476"></a><span class="lineno"> 476</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00477"></a><span class="lineno"> 477</span>  <span class="keywordflow">return</span> numBatches_;</div>
<div class="line"><a name="l00478"></a><span class="lineno"> 478</span>  }</div>
<div class="line"><a name="l00480"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#af38417dd67de2b6cee9d1ee09e501c68"> 480</a></span>  </div>
<div class="line"><a name="l00482"></a><span class="lineno"> 482</span>  <span class="comment">// Protected functions:</span></div>
<div class="line"><a name="l00483"></a><span class="lineno"> 483</span>  <span class="keywordtype">void</span> BITstar::iterate()</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>  <span class="comment">// Keep track of how many iterations we've performed.</span></div>
<div class="line"><a name="l00486"></a><span class="lineno"> 486</span>  ++numIterations_;</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>  <span class="comment">// If the search is done or the queue is empty, we need to populate the queue.</span></div>
<div class="line"><a name="l00489"></a><span class="lineno"> 489</span>  <span class="keywordflow">if</span> (isSearchDone_ || queuePtr_->isEmpty())</div>
<div class="line"><a name="l00490"></a><span class="lineno"> 490</span>  {</div>
<div class="line"><a name="l00491"></a><span class="lineno"> 491</span>  <span class="comment">// Check whether we've exhausted the current approximation.</span></div>
<div class="line"><a name="l00492"></a><span class="lineno"> 492</span>  <span class="keywordflow">if</span> (isFinalSearchOnBatch_ || !hasExactSolution_)</div>
<div class="line"><a name="l00493"></a><span class="lineno"> 493</span>  {</div>
<div class="line"><a name="l00494"></a><span class="lineno"> 494</span>  <span class="comment">// Prune the graph if enabled.</span></div>
<div class="line"><a name="l00495"></a><span class="lineno"> 495</span>  <span class="keywordflow">if</span> (isPruningEnabled_)</div>
<div class="line"><a name="l00496"></a><span class="lineno"> 496</span>  {</div>
<div class="line"><a name="l00497"></a><span class="lineno"> 497</span>  this->prune();</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>  </div>
<div class="line"><a name="l00500"></a><span class="lineno"> 500</span>  <span class="comment">// Add a new batch.</span></div>
<div class="line"><a name="l00501"></a><span class="lineno"> 501</span>  this->newBatch();</div>
<div class="line"><a name="l00502"></a><span class="lineno"> 502</span>  </div>
<div class="line"><a name="l00503"></a><span class="lineno"> 503</span>  <span class="comment">// Set the inflation factor to an initial value.</span></div>
<div class="line"><a name="l00504"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#a9441e73fbec5789e481fbcee9c76d4b1"> 504</a></span>  queuePtr_->setInflationFactor(initialInflationFactor_);</div>
<div class="line"><a name="l00505"></a><span class="lineno"> 505</span>  </div>
<div class="line"><a name="l00506"></a><span class="lineno"> 506</span>  <span class="comment">// Clear the search queue.</span></div>
<div class="line"><a name="l00507"></a><span class="lineno"> 507</span>  queuePtr_->clear();</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>  <span class="comment">// Restart the queue, adding the outgoing edges of the start vertices to the queue.</span></div>
<div class="line"><a name="l00510"></a><span class="lineno"> 510</span>  queuePtr_->insertOutgoingEdgesOfStartVertices();</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="comment">// Set flag to false.</span></div>
<div class="line"><a name="l00513"></a><span class="lineno"> 513</span>  isFinalSearchOnBatch_ = <span class="keyword">false</span>;</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>  <span class="comment">// Set the new truncation factor.</span></div>
<div class="line"><a name="l00516"></a><span class="lineno"> 516</span>  truncationFactor_ =</div>
<div class="line"><a name="l00517"></a><span class="lineno"> 517</span>  1.0 + truncationScalingParameter_ /</div>
<div class="line"><a name="l00518"></a><span class="lineno"> 518</span>  (<span class="keyword">static_cast<</span><span class="keywordtype">float</span><span class="keyword">></span>(graphPtr_->numVertices() + graphPtr_->numSamples()));</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>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00521"></a><span class="lineno"> 521</span>  {</div>
<div class="line"><a name="l00522"></a><span class="lineno"> 522</span>  <span class="comment">// Exhaust the current approximation by performing an uninflated search.</span></div>
<div class="line"><a name="l00523"></a><span class="lineno"> 523</span>  queuePtr_->setInflationFactor(</div>
<div class="line"><a name="l00524"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#a13d6b414a6cf05d37e7c37d3931ccb38"> 524</a></span>  1.0 + inflationScalingParameter_ /</div>
<div class="line"><a name="l00525"></a><span class="lineno"> 525</span>  (<span class="keyword">static_cast<</span><span class="keywordtype">float</span><span class="keyword">></span>(graphPtr_->numVertices() + graphPtr_->numSamples())));</div>
<div class="line"><a name="l00526"></a><span class="lineno"> 526</span>  queuePtr_->rebuildEdgeQueue();</div>
<div class="line"><a name="l00527"></a><span class="lineno"> 527</span>  queuePtr_->insertOutgoingEdgesOfInconsistentVertices();</div>
<div class="line"><a name="l00528"></a><span class="lineno"> 528</span>  queuePtr_->clearInconsistentSet();</div>
<div class="line"><a name="l00529"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#a6849d38db6c966e12fbc2ae575acd98f"> 529</a></span>  isFinalSearchOnBatch_ = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00530"></a><span class="lineno"> 530</span>  }</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>  isSearchDone_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00533"></a><span class="lineno"> 533</span>  }</div>
<div class="line"><a name="l00534"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#a0b681699d607545e82b922138899e41e"> 534</a></span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00535"></a><span class="lineno"> 535</span>  {</div>
<div class="line"><a name="l00536"></a><span class="lineno"> 536</span>  <span class="comment">// Get the most promising edge.</span></div>
<div class="line"><a name="l00537"></a><span class="lineno"> 537</span>  <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a85f2f074b60a176d939867e33d17fc9e">VertexPtrPair</a> edge = queuePtr_->popFrontEdge();</div>
<div class="line"><a name="l00538"></a><span class="lineno"> 538</span>  </div>
<div class="line"><a name="l00539"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BITstar.html#adbd5197b394d63359c072d3e1d6e9339"> 539</a></span>  <span class="comment">// If this edge is already part of the search tree it's a freebie.</span></div>
<div class="line"><a name="l00540"></a><span class="lineno"> 540</span>  <span class="keywordflow">if</span> (edge.second->hasParent() && edge.second->getParent()->getId() == edge.first->getId())</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>  <span class="keywordflow">if</span> (!edge.first->isExpandedOnCurrentSearch())</div>
<div class="line"><a name="l00543"></a><span class="lineno"> 543</span>  {</div>
<div class="line"><a name="l00544"></a><span class="lineno"> 544</span>  edge.first->registerExpansion();</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>  queuePtr_->insertOutgoingEdges(edge.second);</div>
<div class="line"><a name="l00547"></a><span class="lineno"> 547</span>  }</div>
<div class="line"><a name="l00548"></a><span class="lineno"> 548</span>  <span class="comment">// In the best case, can this edge improve our solution given the current graph?</span></div>
<div class="line"><a name="l00549"></a><span class="lineno"> 549</span>  <span class="comment">// g_t(v) + c_hat(v,x) + h_hat(x) < g_t(x_g)?</span></div>
<div class="line"><a name="l00550"></a><span class="lineno"> 550</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (costHelpPtr_->isCostBetterThan(</div>
<div class="line"><a name="l00551"></a><span class="lineno"> 551</span>  costHelpPtr_->inflateCost(costHelpPtr_->currentHeuristicEdge(edge), truncationFactor_),</div>
<div class="line"><a name="l00552"></a><span class="lineno"> 552</span>  bestCost_))</div>
<div class="line"><a name="l00553"></a><span class="lineno"> 553</span>  {</div>
<div class="line"><a name="l00554"></a><span class="lineno"> 554</span>  <span class="comment">// What about improving the current graph?</span></div>
<div class="line"><a name="l00555"></a><span class="lineno"> 555</span>  <span class="comment">// g_t(v) + c_hat(v,x) < g_t(x)?</span></div>
<div class="line"><a name="l00556"></a><span class="lineno"> 556</span>  <span class="keywordflow">if</span> (costHelpPtr_->isCostBetterThan(costHelpPtr_->currentHeuristicToTarget(edge),</div>
<div class="line"><a name="l00557"></a><span class="lineno"> 557</span>  edge.second->getCost()))</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>  <span class="comment">// Ok, so it *could* be a useful edge. Do the work of calculating its cost for real</span></div>
<div class="line"><a name="l00560"></a><span class="lineno"> 560</span>  </div>
<div class="line"><a name="l00561"></a><span class="lineno"> 561</span>  <span class="comment">// Get the true cost of the edge</span></div>
<div class="line"><a name="l00562"></a><span class="lineno"> 562</span>  <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> trueEdgeCost = costHelpPtr_->trueEdgeCost(edge);</div>
<div class="line"><a name="l00563"></a><span class="lineno"> 563</span>  </div>
<div class="line"><a name="l00564"></a><span class="lineno"> 564</span>  <span class="comment">// Can this actual edge ever improve our solution?</span></div>
<div class="line"><a name="l00565"></a><span class="lineno"> 565</span>  <span class="comment">// g_hat(v) + c(v,x) + h_hat(x) < g_t(x_g)?</span></div>
<div class="line"><a name="l00566"></a><span class="lineno"> 566</span>  <span class="keywordflow">if</span> (costHelpPtr_->isCostBetterThan(</div>
<div class="line"><a name="l00567"></a><span class="lineno"> 567</span>  costHelpPtr_->combineCosts(costHelpPtr_->costToComeHeuristic(edge.first), trueEdgeCost,</div>
<div class="line"><a name="l00568"></a><span class="lineno"> 568</span>  costHelpPtr_->costToGoHeuristic(edge.second)),</div>
<div class="line"><a name="l00569"></a><span class="lineno"> 569</span>  bestCost_))</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>  <span class="comment">// Does this edge have a collision?</span></div>
<div class="line"><a name="l00572"></a><span class="lineno"> 572</span>  <span class="keywordflow">if</span> (this->checkEdge(edge))</div>
<div class="line"><a name="l00573"></a><span class="lineno"> 573</span>  {</div>
<div class="line"><a name="l00574"></a><span class="lineno"> 574</span>  <span class="comment">// Remember that this edge has passed the collision checks.</span></div>
<div class="line"><a name="l00575"></a><span class="lineno"> 575</span>  this->whitelistEdge(edge);</div>
<div class="line"><a name="l00576"></a><span class="lineno"> 576</span>  </div>
<div class="line"><a name="l00577"></a><span class="lineno"> 577</span>  <span class="comment">// Does the current edge improve our graph?</span></div>
<div class="line"><a name="l00578"></a><span class="lineno"> 578</span>  <span class="comment">// g_t(v) + c(v,x) < g_t(x)?</span></div>
<div class="line"><a name="l00579"></a><span class="lineno"> 579</span>  <span class="keywordflow">if</span> (costHelpPtr_->isCostBetterThan(</div>
<div class="line"><a name="l00580"></a><span class="lineno"> 580</span>  costHelpPtr_->combineCosts(edge.first->getCost(), trueEdgeCost),</div>
<div class="line"><a name="l00581"></a><span class="lineno"> 581</span>  edge.second->getCost()))</div>
<div class="line"><a name="l00582"></a><span class="lineno"> 582</span>  {</div>
<div class="line"><a name="l00583"></a><span class="lineno"> 583</span>  <span class="comment">// YAAAAH. Add the edge! Allowing for the sample to be removed from free if it is</span></div>
<div class="line"><a name="l00584"></a><span class="lineno"> 584</span>  <span class="comment">// not currently connected and otherwise propagate cost updates to descendants.</span></div>
<div class="line"><a name="l00585"></a><span class="lineno"> 585</span>  <span class="comment">// addEdge will update the queue and handle the extra work that occurs if this edge</span></div>
<div class="line"><a name="l00586"></a><span class="lineno"> 586</span>  <span class="comment">// improves the solution.</span></div>
<div class="line"><a name="l00587"></a><span class="lineno"> 587</span>  this->addEdge(edge, trueEdgeCost);</div>
<div class="line"><a name="l00588"></a><span class="lineno"> 588</span>  </div>
<div class="line"><a name="l00589"></a><span class="lineno"> 589</span>  <span class="comment">// If the path to the goal has changed, we will need to update the cached info about</span></div>
<div class="line"><a name="l00590"></a><span class="lineno"> 590</span>  <span class="comment">// the solution cost or solution length:</span></div>
<div class="line"><a name="l00591"></a><span class="lineno"> 591</span>  this->updateGoalVertex();</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>  <span class="comment">// If this is the first edge that's being expanded in the current search, remember</span></div>
<div class="line"><a name="l00594"></a><span class="lineno"> 594</span>  <span class="comment">// the cost-to-come and the search / approximation ids.</span></div>
<div class="line"><a name="l00595"></a><span class="lineno"> 595</span>  <span class="keywordflow">if</span> (!edge.first->isExpandedOnCurrentSearch())</div>
<div class="line"><a name="l00596"></a><span class="lineno"> 596</span>  {</div>
<div class="line"><a name="l00597"></a><span class="lineno"> 597</span>  edge.first->registerExpansion();</div>
<div class="line"><a name="l00598"></a><span class="lineno"> 598</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="comment">// No else, this edge may be useful at some later date.</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">else</span> <span class="comment">// Remember that this edge is in collision.</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>  this->blacklistEdge(edge);</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>  }</div>
<div class="line"><a name="l00607"></a><span class="lineno"> 607</span>  <span class="comment">// No else, we failed</span></div>
<div class="line"><a name="l00608"></a><span class="lineno"> 608</span>  }</div>
<div class="line"><a name="l00609"></a><span class="lineno"> 609</span>  <span class="comment">// No else, we failed</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></div>
<div class="line"><a name="l00612"></a><span class="lineno"> 612</span>  {</div>
<div class="line"><a name="l00613"></a><span class="lineno"> 613</span>  isSearchDone_ = <span class="keyword">true</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">// Search queue not empty.</span></div>
<div class="line"><a name="l00616"></a><span class="lineno"> 616</span>  }</div>
<div class="line"><a name="l00617"></a><span class="lineno"> 617</span>  </div>
<div class="line"><a name="l00618"></a><span class="lineno"> 618</span>  <span class="keywordtype">void</span> BITstar::newBatch()</div>
<div class="line"><a name="l00619"></a><span class="lineno"> 619</span>  {</div>
<div class="line"><a name="l00620"></a><span class="lineno"> 620</span>  <span class="comment">// Increment the batch counter.</span></div>
<div class="line"><a name="l00621"></a><span class="lineno"> 621</span>  ++numBatches_;</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>  <span class="comment">// Do we need to update our starts or goals?</span></div>
<div class="line"><a name="l00624"></a><span class="lineno"> 624</span>  <span class="keywordflow">if</span> (Planner::pis_.haveMoreStartStates() || Planner::pis_.haveMoreGoalStates())</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>  <span class="comment">// There are new starts/goals to get.</span></div>
<div class="line"><a name="l00627"></a><span class="lineno"> 627</span>  graphPtr_->updateStartAndGoalStates(Planner::pis_, <a class="code" href="namespaceompl_1_1base.html#a1125deb13109d3f27b3acab34d79c09c">ompl::base::plannerAlwaysTerminatingCondition</a>());</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">// No else, we have enough of a problem to do some work, and everything's up to date.</span></div>
<div class="line"><a name="l00630"></a><span class="lineno"> 630</span>  </div>
<div class="line"><a name="l00631"></a><span class="lineno"> 631</span>  <span class="comment">// Add a new batch of samples.</span></div>
<div class="line"><a name="l00632"></a><span class="lineno"> 632</span>  graphPtr_->addNewSamples(samplesPerBatch_);</div>
<div class="line"><a name="l00633"></a><span class="lineno"> 633</span>  }</div>
<div class="line"><a name="l00634"></a><span class="lineno"> 634</span>  </div>
<div class="line"><a name="l00635"></a><span class="lineno"> 635</span>  <span class="keywordtype">void</span> BITstar::prune()</div>
<div class="line"><a name="l00636"></a><span class="lineno"> 636</span>  {</div>
<div class="line"><a name="l00637"></a><span class="lineno"> 637</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00638"></a><span class="lineno"> 638</span>  <span class="keywordflow">if</span> (!isPruningEnabled_)</div>
<div class="line"><a name="l00639"></a><span class="lineno"> 639</span>  {</div>
<div class="line"><a name="l00640"></a><span class="lineno"> 640</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"Pruning is not enabled, but prune() is called nonetheless."</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="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00643"></a><span class="lineno"> 643</span>  </div>
<div class="line"><a name="l00644"></a><span class="lineno"> 644</span>  <span class="comment">// If we don't have an exact solution, we can't prune sensibly.</span></div>
<div class="line"><a name="l00645"></a><span class="lineno"> 645</span>  <span class="keywordflow">if</span> (hasExactSolution_)</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">/* Profiling reveals that pruning is very expensive, mainly because the nearest neighbour structure of</span></div>
<div class="line"><a name="l00648"></a><span class="lineno"> 648</span> <span class="comment"> * the samples has to be updated. On the other hand, nearest neighbour lookup gets more expensive the</span></div>
<div class="line"><a name="l00649"></a><span class="lineno"> 649</span> <span class="comment"> * bigger the structure, so it's a tradeoff. Pruning on every cost update seems insensible, but so does</span></div>
<div class="line"><a name="l00650"></a><span class="lineno"> 650</span> <span class="comment"> * never pruning at all. The criteria to prune should depend on how many vertices/samples there are and</span></div>
<div class="line"><a name="l00651"></a><span class="lineno"> 651</span> <span class="comment"> * how many of them could be pruned, as the decrease in cost associated with nearest neighbour lookup</span></div>
<div class="line"><a name="l00652"></a><span class="lineno"> 652</span> <span class="comment"> * for fewer samples must justify the cost of pruning. It turns out that counting is affordable, so we</span></div>
<div class="line"><a name="l00653"></a><span class="lineno"> 653</span> <span class="comment"> * don't need to use any proxy here. */</span></div>
<div class="line"><a name="l00654"></a><span class="lineno"> 654</span>  </div>
<div class="line"><a name="l00655"></a><span class="lineno"> 655</span>  <span class="comment">// Count the number of samples that could be pruned.</span></div>
<div class="line"><a name="l00656"></a><span class="lineno"> 656</span>  <span class="keyword">auto</span> samples = graphPtr_->getCopyOfSamples();</div>
<div class="line"><a name="l00657"></a><span class="lineno"> 657</span>  <span class="keyword">auto</span> numSamplesThatCouldBePruned =</div>
<div class="line"><a name="l00658"></a><span class="lineno"> 658</span>  std::count_if(samples.begin(), samples.end(), [<span class="keyword">this</span>](<span class="keyword">const</span> <span class="keyword">auto</span>& sample){</div>
<div class="line"><a name="l00659"></a><span class="lineno"> 659</span>  return graphPtr_->canSampleBePruned(sample);</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>  </div>
<div class="line"><a name="l00662"></a><span class="lineno"> 662</span>  <span class="comment">// Only prune if the decrease in number of samples and the associated decrease in nearest neighbour</span></div>
<div class="line"><a name="l00663"></a><span class="lineno"> 663</span>  <span class="comment">// lookup cost justifies the cost of pruning. There has to be a way to make this more formal, and less</span></div>
<div class="line"><a name="l00664"></a><span class="lineno"> 664</span>  <span class="comment">// knob-turney, right?</span></div>
<div class="line"><a name="l00665"></a><span class="lineno"> 665</span>  <span class="keywordflow">if</span> (<span class="keyword">static_cast<</span><span class="keywordtype">float</span><span class="keyword">></span>(numSamplesThatCouldBePruned) /</div>
<div class="line"><a name="l00666"></a><span class="lineno"> 666</span>  <span class="keyword">static_cast<</span><span class="keywordtype">float</span><span class="keyword">></span>(graphPtr_->numSamples() + graphPtr_->numVertices()) >=</div>
<div class="line"><a name="l00667"></a><span class="lineno"> 667</span>  pruneFraction_)</div>
<div class="line"><a name="l00668"></a><span class="lineno"> 668</span>  {</div>
<div class="line"><a name="l00669"></a><span class="lineno"> 669</span>  <span class="comment">// Get the current informed measure of the problem space.</span></div>
<div class="line"><a name="l00670"></a><span class="lineno"> 670</span>  <span class="keywordtype">double</span> informedMeasure = graphPtr_->getInformedMeasure(bestCost_);</div>
<div class="line"><a name="l00671"></a><span class="lineno"> 671</span>  </div>
<div class="line"><a name="l00672"></a><span class="lineno"> 672</span>  <span class="comment">// Increment the pruning counter:</span></div>
<div class="line"><a name="l00673"></a><span class="lineno"> 673</span>  ++numPrunings_;</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>  <span class="comment">// Prune the graph.</span></div>
<div class="line"><a name="l00676"></a><span class="lineno"> 676</span>  std::pair<unsigned int, unsigned int> numPruned = graphPtr_->prune(informedMeasure);</div>
<div class="line"><a name="l00677"></a><span class="lineno"> 677</span>  </div>
<div class="line"><a name="l00678"></a><span class="lineno"> 678</span>  <span class="comment">// Store the cost at which we pruned:</span></div>
<div class="line"><a name="l00679"></a><span class="lineno"> 679</span>  prunedCost_ = bestCost_;</div>
<div class="line"><a name="l00680"></a><span class="lineno"> 680</span>  </div>
<div class="line"><a name="l00681"></a><span class="lineno"> 681</span>  <span class="comment">// Also store the measure.</span></div>
<div class="line"><a name="l00682"></a><span class="lineno"> 682</span>  prunedMeasure_ = informedMeasure;</div>
<div class="line"><a name="l00683"></a><span class="lineno"> 683</span>  </div>
<div class="line"><a name="l00684"></a><span class="lineno"> 684</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Pruning disconnected %d vertices from the tree and completely removed %d samples."</span>,</div>
<div class="line"><a name="l00685"></a><span class="lineno"> 685</span>  Planner::getName().c_str(), numPruned.first, numPruned.second);</div>
<div class="line"><a name="l00686"></a><span class="lineno"> 686</span>  }</div>
<div class="line"><a name="l00687"></a><span class="lineno"> 687</span>  }</div>
<div class="line"><a name="l00688"></a><span class="lineno"> 688</span>  <span class="comment">// No else.</span></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="keywordtype">void</span> BITstar::blacklistEdge(<span class="keyword">const</span> VertexPtrPair &edge)<span class="keyword"> const</span></div>
<div class="line"><a name="l00692"></a><span class="lineno"> 692</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00693"></a><span class="lineno"> 693</span>  <span class="comment">// We store the actual blacklist with the parent vertex for efficient lookup.</span></div>
<div class="line"><a name="l00694"></a><span class="lineno"> 694</span>  edge.first->blacklistChild(edge.second);</div>
<div class="line"><a name="l00695"></a><span class="lineno"> 695</span>  }</div>
<div class="line"><a name="l00696"></a><span class="lineno"> 696</span>  </div>
<div class="line"><a name="l00697"></a><span class="lineno"> 697</span>  <span class="keywordtype">void</span> BITstar::whitelistEdge(<span class="keyword">const</span> VertexPtrPair &edge)<span class="keyword"> const</span></div>
<div class="line"><a name="l00698"></a><span class="lineno"> 698</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00699"></a><span class="lineno"> 699</span>  <span class="comment">// We store the actual whitelist with the parent vertex for efficient lookup.</span></div>
<div class="line"><a name="l00700"></a><span class="lineno"> 700</span>  edge.first->whitelistChild(edge.second);</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>  </div>
<div class="line"><a name="l00703"></a><span class="lineno"> 703</span>  <span class="keywordtype">void</span> BITstar::publishSolution()</div>
<div class="line"><a name="l00704"></a><span class="lineno"> 704</span>  {</div>
<div class="line"><a name="l00705"></a><span class="lineno"> 705</span>  <span class="comment">// Variable</span></div>
<div class="line"><a name="l00706"></a><span class="lineno"> 706</span>  <span class="comment">// The reverse path of state pointers</span></div>
<div class="line"><a name="l00707"></a><span class="lineno"> 707</span>  std::vector<const ompl::base::State *> reversePath;</div>
<div class="line"><a name="l00708"></a><span class="lineno"> 708</span>  <span class="comment">// Allocate a path geometric</span></div>
<div class="line"><a name="l00709"></a><span class="lineno"> 709</span>  <span class="keyword">auto</span> pathGeoPtr = std::make_shared<ompl::geometric::PathGeometric>(Planner::si_);</div>
<div class="line"><a name="l00710"></a><span class="lineno"> 710</span>  </div>
<div class="line"><a name="l00711"></a><span class="lineno"> 711</span>  <span class="comment">// Get the reversed path</span></div>
<div class="line"><a name="l00712"></a><span class="lineno"> 712</span>  reversePath = this->bestPathFromGoalToStart();</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>  <span class="comment">// Now iterate that vector in reverse, putting the states into the path geometric</span></div>
<div class="line"><a name="l00715"></a><span class="lineno"> 715</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &solnState : boost::adaptors::reverse(reversePath))</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>  pathGeoPtr->append(solnState);</div>
<div class="line"><a name="l00718"></a><span class="lineno"> 718</span>  }</div>
<div class="line"><a name="l00719"></a><span class="lineno"> 719</span>  </div>
<div class="line"><a name="l00720"></a><span class="lineno"> 720</span>  <span class="comment">// Now create the solution</span></div>
<div class="line"><a name="l00721"></a><span class="lineno"> 721</span>  <a class="code" href="structompl_1_1base_1_1PlannerSolution.html">ompl::base::PlannerSolution</a> soln(pathGeoPtr);</div>
<div class="line"><a name="l00722"></a><span class="lineno"> 722</span>  </div>
<div class="line"><a name="l00723"></a><span class="lineno"> 723</span>  <span class="comment">// Mark the name:</span></div>
<div class="line"><a name="l00724"></a><span class="lineno"> 724</span>  soln.setPlannerName(Planner::getName());</div>
<div class="line"><a name="l00725"></a><span class="lineno"> 725</span>  </div>
<div class="line"><a name="l00726"></a><span class="lineno"> 726</span>  <span class="comment">// Mark as approximate if not exact:</span></div>
<div class="line"><a name="l00727"></a><span class="lineno"> 727</span>  <span class="keywordflow">if</span> (!hasExactSolution_ && graphPtr_->getTrackApproximateSolutions())</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>  soln.setApproximate(graphPtr_->smallestDistanceToGoal());</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">// Mark whether the solution met the optimization objective:</span></div>
<div class="line"><a name="l00733"></a><span class="lineno"> 733</span>  soln.setOptimized(Planner::pdef_-><a class="code" href="namespaceompl_1_1app.html#af450723bcda35917258743668723789f">getOptimizationObjective</a>(), bestCost_,</div>
<div class="line"><a name="l00734"></a><span class="lineno"> 734</span>  Planner::pdef_-><a class="code" href="namespaceompl_1_1app.html#af450723bcda35917258743668723789f">getOptimizationObjective</a>()->isSatisfied(bestCost_));</div>
<div class="line"><a name="l00735"></a><span class="lineno"> 735</span>  </div>
<div class="line"><a name="l00736"></a><span class="lineno"> 736</span>  <span class="comment">// Add the solution to the Problem Definition:</span></div>
<div class="line"><a name="l00737"></a><span class="lineno"> 737</span>  Planner::pdef_->addSolutionPath(soln);</div>
<div class="line"><a name="l00738"></a><span class="lineno"> 738</span>  }</div>
<div class="line"><a name="l00739"></a><span class="lineno"> 739</span>  </div>
<div class="line"><a name="l00740"></a><span class="lineno"> 740</span>  std::vector<const ompl::base::State *> BITstar::bestPathFromGoalToStart()<span class="keyword"> const</span></div>
<div class="line"><a name="l00741"></a><span class="lineno"> 741</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00742"></a><span class="lineno"> 742</span>  <span class="comment">// Variables:</span></div>
<div class="line"><a name="l00743"></a><span class="lineno"> 743</span>  <span class="comment">// A vector of states from goal->start:</span></div>
<div class="line"><a name="l00744"></a><span class="lineno"> 744</span>  std::vector<const ompl::base::State *> reversePath;</div>
<div class="line"><a name="l00745"></a><span class="lineno"> 745</span>  <span class="comment">// The vertex used to ascend up from the goal:</span></div>
<div class="line"><a name="l00746"></a><span class="lineno"> 746</span>  <a class="code" href="classompl_1_1geometric_1_1BITstar.html#a8a2c2f01236fd3977dd42e1776b17e48">VertexConstPtr</a> curVertex;</div>
<div class="line"><a name="l00747"></a><span class="lineno"> 747</span>  </div>
<div class="line"><a name="l00748"></a><span class="lineno"> 748</span>  <span class="comment">// Iterate up the chain from the goal, creating a backwards vector:</span></div>
<div class="line"><a name="l00749"></a><span class="lineno"> 749</span>  <span class="keywordflow">if</span> (hasExactSolution_)</div>
<div class="line"><a name="l00750"></a><span class="lineno"> 750</span>  {</div>
<div class="line"><a name="l00751"></a><span class="lineno"> 751</span>  <span class="comment">// Start at vertex in the goal</span></div>
<div class="line"><a name="l00752"></a><span class="lineno"> 752</span>  curVertex = curGoalVertex_;</div>
<div class="line"><a name="l00753"></a><span class="lineno"> 753</span>  }</div>
<div class="line"><a name="l00754"></a><span class="lineno"> 754</span>  <span class="keywordflow">else</span> <span class="keywordflow">if</span> (!hasExactSolution_ && graphPtr_->getTrackApproximateSolutions())</div>
<div class="line"><a name="l00755"></a><span class="lineno"> 755</span>  {</div>
<div class="line"><a name="l00756"></a><span class="lineno"> 756</span>  <span class="comment">// Start at the vertex closest to the goal</span></div>
<div class="line"><a name="l00757"></a><span class="lineno"> 757</span>  curVertex = graphPtr_->closestVertexToGoal();</div>
<div class="line"><a name="l00758"></a><span class="lineno"> 758</span>  }</div>
<div class="line"><a name="l00759"></a><span class="lineno"> 759</span>  <span class="keywordflow">else</span></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">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"bestPathFromGoalToStart called without an exact or approximate solution."</span>);</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>  </div>
<div class="line"><a name="l00764"></a><span class="lineno"> 764</span>  <span class="comment">// Insert the goal into the path</span></div>
<div class="line"><a name="l00765"></a><span class="lineno"> 765</span>  reversePath.push_back(curVertex->state());</div>
<div class="line"><a name="l00766"></a><span class="lineno"> 766</span>  </div>
<div class="line"><a name="l00767"></a><span class="lineno"> 767</span>  <span class="comment">// Then, use the vertex pointer like an iterator. Starting at the goal, we iterate up the chain pushing the</span></div>
<div class="line"><a name="l00768"></a><span class="lineno"> 768</span>  <span class="comment">// *parent* of the iterator into the vector until the vertex has no parent.</span></div>
<div class="line"><a name="l00769"></a><span class="lineno"> 769</span>  <span class="comment">// This will allows us to add the start (as the parent of the first child) and then stop when we get to the</span></div>
<div class="line"><a name="l00770"></a><span class="lineno"> 770</span>  <span class="comment">// start itself, avoiding trying to find its nonexistent child</span></div>
<div class="line"><a name="l00771"></a><span class="lineno"> 771</span>  <span class="keywordflow">for</span> (<span class="comment">/*Already allocated & initialized*/</span>; !curVertex->isRoot(); curVertex = curVertex->getParent())</div>
<div class="line"><a name="l00772"></a><span class="lineno"> 772</span>  {</div>
<div class="line"><a name="l00773"></a><span class="lineno"> 773</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00774"></a><span class="lineno"> 774</span>  <span class="comment">// Check the case where the chain ends incorrectly.</span></div>
<div class="line"><a name="l00775"></a><span class="lineno"> 775</span>  <span class="keywordflow">if</span> (curVertex->hasParent() == <span class="keyword">false</span>)</div>
<div class="line"><a name="l00776"></a><span class="lineno"> 776</span>  {</div>
<div class="line"><a name="l00777"></a><span class="lineno"> 777</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"The path to the goal does not originate at a start state. Something went "</span></div>
<div class="line"><a name="l00778"></a><span class="lineno"> 778</span>  <span class="stringliteral">"wrong."</span>);</div>
<div class="line"><a name="l00779"></a><span class="lineno"> 779</span>  }</div>
<div class="line"><a name="l00780"></a><span class="lineno"> 780</span> <span class="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00781"></a><span class="lineno"> 781</span>  </div>
<div class="line"><a name="l00782"></a><span class="lineno"> 782</span>  <span class="comment">// Push back the parent into the vector as a state pointer:</span></div>
<div class="line"><a name="l00783"></a><span class="lineno"> 783</span>  reversePath.push_back(curVertex->getParent()->state());</div>
<div class="line"><a name="l00784"></a><span class="lineno"> 784</span>  }</div>
<div class="line"><a name="l00785"></a><span class="lineno"> 785</span>  <span class="keywordflow">return</span> reversePath;</div>
<div class="line"><a name="l00786"></a><span class="lineno"> 786</span>  }</div>
<div class="line"><a name="l00787"></a><span class="lineno"> 787</span>  </div>
<div class="line"><a name="l00788"></a><span class="lineno"> 788</span>  <span class="keywordtype">bool</span> BITstar::checkEdge(<span class="keyword">const</span> VertexConstPtrPair &edge)</div>
<div class="line"><a name="l00789"></a><span class="lineno"> 789</span>  {</div>
<div class="line"><a name="l00790"></a><span class="lineno"> 790</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00791"></a><span class="lineno"> 791</span>  <span class="keywordflow">if</span> (edge.first->isBlacklistedAsChild(edge.second))</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>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"A blacklisted edge made it into the edge queue."</span>);</div>
<div class="line"><a name="l00794"></a><span class="lineno"> 794</span>  }</div>
<div class="line"><a name="l00795"></a><span class="lineno"> 795</span> <span class="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00796"></a><span class="lineno"> 796</span>  <span class="comment">// If this is a whitelisted edge, there's no need to do (repeat) the collision checking.</span></div>
<div class="line"><a name="l00797"></a><span class="lineno"> 797</span>  <span class="keywordflow">if</span> (edge.first->isWhitelistedAsChild(edge.second))</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>  <span class="keywordflow">return</span> <span class="keyword">true</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="keywordflow">else</span> <span class="comment">// This is a new edge, we need to check whether it is feasible.</span></div>
<div class="line"><a name="l00802"></a><span class="lineno"> 802</span>  {</div>
<div class="line"><a name="l00803"></a><span class="lineno"> 803</span>  ++numEdgeCollisionChecks_;</div>
<div class="line"><a name="l00804"></a><span class="lineno"> 804</span>  <span class="keywordflow">return</span> Planner::si_->checkMotion(edge.first->state(), edge.second->state());</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>  }</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>  <span class="keywordtype">void</span> BITstar::addEdge(<span class="keyword">const</span> VertexPtrPair &edge, <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &edgeCost)</div>
<div class="line"><a name="l00809"></a><span class="lineno"> 809</span>  {</div>
<div class="line"><a name="l00810"></a><span class="lineno"> 810</span> <span class="preprocessor">#ifdef BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00811"></a><span class="lineno"> 811</span>  <span class="keywordflow">if</span> (edge.first->isInTree() == <span class="keyword">false</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"> 813</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"Adding an edge from a vertex not connected to the graph"</span>);</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>  <span class="keywordflow">if</span> (costHelpPtr_->isCostEquivalentTo(costHelpPtr_->trueEdgeCost(edge), edgeCost) == <span class="keyword">false</span>)</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>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">ompl::Exception</a>(<span class="stringliteral">"You have passed the wrong edge cost to addEdge."</span>);</div>
<div class="line"><a name="l00818"></a><span class="lineno"> 818</span>  }</div>
<div class="line"><a name="l00819"></a><span class="lineno"> 819</span> <span class="preprocessor">#endif // BITSTAR_DEBUG</span></div>
<div class="line"><a name="l00820"></a><span class="lineno"> 820</span>  </div>
<div class="line"><a name="l00821"></a><span class="lineno"> 821</span>  <span class="comment">// If the child already has a parent, this is a rewiring.</span></div>
<div class="line"><a name="l00822"></a><span class="lineno"> 822</span>  <span class="keywordflow">if</span> (edge.second->hasParent())</div>
<div class="line"><a name="l00823"></a><span class="lineno"> 823</span>  {</div>
<div class="line"><a name="l00824"></a><span class="lineno"> 824</span>  <span class="comment">// Replace the old parent.</span></div>
<div class="line"><a name="l00825"></a><span class="lineno"> 825</span>  this->replaceParent(edge, edgeCost);</div>
<div class="line"><a name="l00826"></a><span class="lineno"> 826</span>  } <span class="comment">// If not, we add the vertex without replaceing a parent.</span></div>
<div class="line"><a name="l00827"></a><span class="lineno"> 827</span>  <span class="keywordflow">else</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="comment">// Add a parent to the child.</span></div>
<div class="line"><a name="l00830"></a><span class="lineno"> 830</span>  edge.second->addParent(edge.first, edgeCost);</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="comment">// Add a child to the parent.</span></div>
<div class="line"><a name="l00833"></a><span class="lineno"> 833</span>  edge.first->addChild(edge.second);</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="comment">// Add the vertex to the set of vertices.</span></div>
<div class="line"><a name="l00836"></a><span class="lineno"> 836</span>  graphPtr_->registerAsVertex(edge.second);</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>  </div>
<div class="line"><a name="l00839"></a><span class="lineno"> 839</span>  <span class="comment">// If the vertex hasn't already been expanded, insert its outgoing edges</span></div>
<div class="line"><a name="l00840"></a><span class="lineno"> 840</span>  <span class="keywordflow">if</span> (!edge.second->isExpandedOnCurrentSearch())</div>
<div class="line"><a name="l00841"></a><span class="lineno"> 841</span>  {</div>
<div class="line"><a name="l00842"></a><span class="lineno"> 842</span>  queuePtr_->insertOutgoingEdges(edge.second);</div>
<div class="line"><a name="l00843"></a><span class="lineno"> 843</span>  }</div>
<div class="line"><a name="l00844"></a><span class="lineno"> 844</span>  <span class="keywordflow">else</span> <span class="comment">// If the vertex has already been expanded, remember it as inconsistent.</span></div>
<div class="line"><a name="l00845"></a><span class="lineno"> 845</span>  {</div>
<div class="line"><a name="l00846"></a><span class="lineno"> 846</span>  queuePtr_->addToInconsistentSet(edge.second);</div>
<div class="line"><a name="l00847"></a><span class="lineno"> 847</span>  }</div>