-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathBLITstar_8h_source.html
More file actions
492 lines (490 loc) · 81.8 KB
/
BLITstar_8h_source.html
File metadata and controls
492 lines (490 loc) · 81.8 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
<!-- HTML header for doxygen 1.14.0-->
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US" class="light-mode">
<head>
<meta name="color-scheme" content="light">
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
<meta name="generator" content="Doxygen 1.16.1"/>
<meta name="viewport" content="width=device-width, initial-scale=1"/>
<title>ompl: ompl/geometric/planners/lazyinformedtrees/BLITstar.h Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<script type="text/javascript" src="clipboard.js"></script>
<script type="text/javascript" src="cookie.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">
$(function() { init_search(); });
</script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
<link href="ompl.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="demos.html">Demos</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>
<a class="dropdown-item" href="https://github.com/ompl/ompl">OMPL on GitHub</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>
</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">
<span id="MSearchSelect" class="search-icon" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()"><span class="search-icon-dropdown"></span></span>
<input type="text" id="MSearchField" value="" placeholder="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()"><div id="MSearchCloseImg" class="close-icon"></div></a>
</span>
</div>
</div>
</nav>
<div class="container" role="main">
<div>
<!-- Generated by Doxygen 1.16.1 -->
<script type="text/javascript">
var searchBox = new SearchBox("searchBox", "search/",'.html');
</script>
<script type="text/javascript">
$(function() { codefold.init(); });
</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">
<div id="MSearchResults">
<div class="SRPage">
<div id="SRIndex">
<div id="SRResults"></div>
<div class="SRStatus" id="Loading">Loading...</div>
<div class="SRStatus" id="Searching">Searching...</div>
<div class="SRStatus" id="NoMatches">No Matches</div>
</div>
</div>
</div>
</div>
<div id="nav-path" class="navpath">
<ul>
<li class="navelem"><b>ompl</b></li><li class="navelem"><b>geometric</b></li><li class="navelem"><b>planners</b></li><li class="navelem"><b>lazyinformedtrees</b></li> </ul>
</div>
</div><!-- top -->
<div id="doc-content">
<div class="header">
<div class="headertitle"><div class="title">BLITstar.h</div></div>
</div><!--header-->
<div class="contents">
<div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span><span class="comment">/*********************************************************************</span></div>
<div class="line"><a id="l00002" name="l00002"></a><span class="lineno"> 2</span><span class="comment"> * Software License Agreement (BSD License)</span></div>
<div class="line"><a id="l00003" name="l00003"></a><span class="lineno"> 3</span><span class="comment"> *</span></div>
<div class="line"><a id="l00004" name="l00004"></a><span class="lineno"> 4</span><span class="comment"> * Copyright (c) 2025, University of New Hampshire</span></div>
<div class="line"><a id="l00005" name="l00005"></a><span class="lineno"> 5</span><span class="comment"> * All rights reserved.</span></div>
<div class="line"><a id="l00006" name="l00006"></a><span class="lineno"> 6</span><span class="comment"> *</span></div>
<div class="line"><a id="l00007" 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 id="l00008" 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 id="l00009" name="l00009"></a><span class="lineno"> 9</span><span class="comment"> * are met:</span></div>
<div class="line"><a id="l00010" name="l00010"></a><span class="lineno"> 10</span><span class="comment"> *</span></div>
<div class="line"><a id="l00011" 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 id="l00012" 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 id="l00013" 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 id="l00014" 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 id="l00015" 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 id="l00016" name="l00016"></a><span class="lineno"> 16</span><span class="comment"> * with the distribution.</span></div>
<div class="line"><a id="l00017" name="l00017"></a><span class="lineno"> 17</span><span class="comment"> * * Neither the names of the copyright holders nor the names of its</span></div>
<div class="line"><a id="l00018" 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 id="l00019" 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 id="l00020" name="l00020"></a><span class="lineno"> 20</span><span class="comment"> *</span></div>
<div class="line"><a id="l00021" 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 id="l00022" 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 id="l00023" 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 id="l00024" 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 id="l00025" 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 id="l00026" name="l00026"></a><span class="lineno"> 26</span><span class="comment"> * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span></div>
<div class="line"><a id="l00027" 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 id="l00028" 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 id="l00029" 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 id="l00030" 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 id="l00031" 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 id="l00032" name="l00032"></a><span class="lineno"> 32</span><span class="comment"> * POSSIBILITY OF SUCH DAMAGE.</span></div>
<div class="line"><a id="l00033" name="l00033"></a><span class="lineno"> 33</span><span class="comment"> *********************************************************************/</span></div>
<div class="line"><a id="l00034" name="l00034"></a><span class="lineno"> 34</span><span class="comment">/*********************************************************************</span></div>
<div class="line"><a id="l00035" name="l00035"></a><span class="lineno"> 35</span><span class="comment"> * Attribution Notice:</span></div>
<div class="line"><a id="l00036" name="l00036"></a><span class="lineno"> 36</span><span class="comment"> *</span></div>
<div class="line"><a id="l00037" name="l00037"></a><span class="lineno"> 37</span><span class="comment"> * This file contains code partially adapted from the AIT* and BIT* planners</span></div>
<div class="line"><a id="l00038" name="l00038"></a><span class="lineno"> 38</span><span class="comment"> * in the Open Motion Planning Library (OMPL). Elements such as sampling</span></div>
<div class="line"><a id="l00039" name="l00039"></a><span class="lineno"> 39</span><span class="comment"> * structure and queue management are based on those planners.</span></div>
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"> 40</span><span class="comment"> *</span></div>
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"> 41</span><span class="comment"> * The overall planning strategy and key contributions for BLIT* were developed</span></div>
<div class="line"><a id="l00042" name="l00042"></a><span class="lineno"> 42</span><span class="comment"> * independently by Yi Wang.</span></div>
<div class="line"><a id="l00043" name="l00043"></a><span class="lineno"> 43</span><span class="comment"> *********************************************************************/</span></div>
<div class="line"><a id="l00044" name="l00044"></a><span class="lineno"> 44</span> </div>
<div class="line"><a id="l00045" name="l00045"></a><span class="lineno"> 45</span><span class="comment">// Authors: Yi Wang, Eyal Weiss, Bingxian Mu, Oren Salzman</span></div>
<div class="line"><a id="l00046" name="l00046"></a><span class="lineno"> 46</span> </div>
<div class="line"><a id="l00047" name="l00047"></a><span class="lineno"> 47</span><span class="preprocessor">#ifndef OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_BLITSTAR_</span></div>
<div class="line"><a id="l00048" name="l00048"></a><span class="lineno"> 48</span><span class="preprocessor">#define OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_BLITSTAR_</span></div>
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"> 49</span> </div>
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"> 50</span><span class="preprocessor">#include <algorithm></span></div>
<div class="line"><a id="l00051" name="l00051"></a><span class="lineno"> 51</span><span class="preprocessor">#include <memory></span></div>
<div class="line"><a id="l00052" name="l00052"></a><span class="lineno"> 52</span><span class="preprocessor">#include <unordered_map></span></div>
<div class="line"><a id="l00053" name="l00053"></a><span class="lineno"> 53</span><span class="preprocessor">#include "ompl/base/Planner.h"</span></div>
<div class="line"><a id="l00054" name="l00054"></a><span class="lineno"> 54</span><span class="preprocessor">#include <unsupported/Eigen/Polynomials></span></div>
<div class="line"><a id="l00055" name="l00055"></a><span class="lineno"> 55</span><span class="preprocessor">#include "ompl/geometric/PathGeometric.h"</span></div>
<div class="line"><a id="l00056" name="l00056"></a><span class="lineno"> 56</span><span class="preprocessor">#include "ompl/geometric/planners/lazyinformedtrees/blitstar/ImplicitGraph.h"</span></div>
<div class="line"><a id="l00057" name="l00057"></a><span class="lineno"> 57</span><span class="preprocessor">#include "ompl/geometric/planners/lazyinformedtrees/blitstar/Vertex.h"</span></div>
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"> 58</span><span class="preprocessor">#include "ompl/geometric/planners/lazyinformedtrees/blitstar/Queuetypes.h"</span></div>
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"> 59</span> </div>
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"> 60</span><span class="preprocessor">#include <chrono></span></div>
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"> 61</span><span class="keyword">using namespace </span>std::chrono;</div>
<div class="line"><a id="l00062" name="l00062"></a><span class="lineno"> 62</span><span class="keyword">namespace </span><a class="code hl_namespace" href="namespaceompl.html">ompl</a></div>
<div class="line"><a id="l00063" name="l00063"></a><span class="lineno"> 63</span>{</div>
<div class="line"><a id="l00064" name="l00064"></a><span class="lineno"> 64</span> <span class="keyword">namespace </span><a class="code hl_namespace" href="namespaceompl_1_1geometric.html">geometric</a></div>
<div class="line"><a id="l00065" name="l00065"></a><span class="lineno"> 65</span> {</div>
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"> 80</span> </div>
<div class="foldopen" id="foldopen00081" data-start="{" data-end="};">
<div class="line"><a id="l00081" name="l00081"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BLITstar.html"> 81</a></span> <span class="keyword">class </span><a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a9fcdc97efcbe88a6168ef781f882c752">BLITstar</a> : <span class="keyword">public</span> <a class="code hl_class" href="classompl_1_1base_1_1Planner.html">ompl::base::Planner</a></div>
<div class="line"><a id="l00082" name="l00082"></a><span class="lineno"> 82</span> {</div>
<div class="line"><a id="l00083" name="l00083"></a><span class="lineno"> 83</span> <span class="keyword">public</span>:</div>
<div class="line"><a id="l00085" name="l00085"></a><span class="lineno"> 85</span> <span class="keyword">explicit</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a9fcdc97efcbe88a6168ef781f882c752">BLITstar</a>(<span class="keyword">const</span> ompl::base::SpaceInformationPtr &spaceInformation);</div>
<div class="line"><a id="l00086" name="l00086"></a><span class="lineno"> 86</span></div>
<div class="line"><a id="l00088" name="l00088"></a><span class="lineno"> 88</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#af24abbf20d6e3b838864b44803be7496">~BLITstar</a>();</div>
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"> 89</span></div>
<div class="line"><a id="l00091" name="l00091"></a><span class="lineno"> 91</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a2e11939b4f5d06d743f03207e4059bb7">setup</a>() <span class="keyword">override</span>;</div>
<div class="line"><a id="l00092" name="l00092"></a><span class="lineno"> 92</span></div>
<div class="line"><a id="l00094" name="l00094"></a><span class="lineno"> 94</span> <a class="code hl_enumeration" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ad7ca75689a41846bbf0c9f7647dcca3a">ensureSetup</a>();</div>
<div class="line"><a id="l00095" name="l00095"></a><span class="lineno"> 95</span></div>
<div class="line"><a id="l00097" name="l00097"></a><span class="lineno"> 97</span> <a class="code hl_enumeration" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a></div>
<div class="line"><a id="l00098" name="l00098"></a><span class="lineno"> 98</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a89f1a931b36ffe3dc90783e085ba5595">ensureStartAndGoalStates</a>(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a> &terminationCondition);</div>
<div class="line"><a id="l00099" name="l00099"></a><span class="lineno"> 99</span></div>
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a662354a31a8627a4684c17e58fdc555e">clear</a>() <span class="keyword">override</span>;</div>
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span></div>
<div class="line"><a id="l00104" name="l00104"></a><span class="lineno"> 104</span> <a class="code hl_struct" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a></div>
<div class="line"><a id="l00105" name="l00105"></a><span class="lineno"> 105</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a20acf9a45d6b214587a36d401b7db7fd">solve</a>(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a> &terminationCondition) <span class="keyword">override</span>;</div>
<div class="line"><a id="l00106" name="l00106"></a><span class="lineno"> 106</span></div>
<div class="line"><a id="l00108" name="l00108"></a><span class="lineno"> 108</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#abfdb2d59132d25abd2b5dd33b437def9">getPlannerData</a>(<a class="code hl_class" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> &data) <span class="keyword">const override</span>;</div>
<div class="line"><a id="l00109" name="l00109"></a><span class="lineno"> 109</span></div>
<div class="line"><a id="l00111" name="l00111"></a><span class="lineno"> 111</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a999619bb38cc4cf2ae7c5caabdcdcdbc">setBatchSize</a>(std::size_t batchSize);</div>
<div class="line"><a id="l00112" name="l00112"></a><span class="lineno"> 112</span></div>
<div class="line"><a id="l00114" name="l00114"></a><span class="lineno"> 114</span> std::size_t <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a95d166539f25ef236d39406edf3bdb65">getBatchSize</a>() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00115" name="l00115"></a><span class="lineno"> 115</span></div>
<div class="line"><a id="l00117" name="l00117"></a><span class="lineno"> 117</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ac86620e8396f059553c2194e5b1793a4">setRewireFactor</a>(<span class="keywordtype">double</span> rewireFactor);</div>
<div class="line"><a id="l00118" name="l00118"></a><span class="lineno"> 118</span></div>
<div class="line"><a id="l00120" name="l00120"></a><span class="lineno"> 120</span> <span class="keywordtype">double</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ab81f56c18cf2d198785da5f0c225cafe">getRewireFactor</a>() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00121" name="l00121"></a><span class="lineno"> 121</span></div>
<div class="line"><a id="l00123" name="l00123"></a><span class="lineno"> 123</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a28a1aeb65335f8f50d71645903b132fa">enablePruning</a>(<span class="keywordtype">bool</span> prune);</div>
<div class="line"><a id="l00124" name="l00124"></a><span class="lineno"> 124</span></div>
<div class="line"><a id="l00126" name="l00126"></a><span class="lineno"> 126</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a474a2063cc0bc73afd8f30108bde8fa8">isPruningEnabled</a>() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00127" name="l00127"></a><span class="lineno"> 127</span></div>
<div class="line"><a id="l00129" name="l00129"></a><span class="lineno"> 129</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a65f06eb63257965203f381ef006d4a6c">setUseKNearest</a>(<span class="keywordtype">bool</span> useKNearest);</div>
<div class="line"><a id="l00130" name="l00130"></a><span class="lineno"> 130</span></div>
<div class="line"><a id="l00132" name="l00132"></a><span class="lineno"> 132</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a18d32dba4d2dd41af3f356a6170b08da">getUseKNearest</a>() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00133" name="l00133"></a><span class="lineno"> 133</span></div>
<div class="line"><a id="l00135" name="l00135"></a><span class="lineno"> 135</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ac65310d23b7d78195f88094f1483a3e9">setMaxNumberOfGoals</a>(<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> numberOfGoals);</div>
<div class="line"><a id="l00136" name="l00136"></a><span class="lineno"> 136</span></div>
<div class="line"><a id="l00138" name="l00138"></a><span class="lineno"> 138</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a79d38cea98702a653e6aa479b9761ab2">getMaxNumberOfGoals</a>() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00139" name="l00139"></a><span class="lineno"> 139</span></div>
<div class="line"><a id="l00141" name="l00141"></a><span class="lineno"> 141</span></div>
<div class="line"><a id="l00143" name="l00143"></a><span class="lineno"> 143</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#aa591f363bc895fee624dcf0ca68417ec">SCD</a>(<span class="keyword">const</span> blitstar::keyEdgePair &edge);</div>
<div class="line"><a id="l00144" name="l00144"></a><span class="lineno"> 144</span> <span class="keywordtype">bool</span> CCD(<span class="keyword">const</span> blitstar::keyEdgePair &edge);</div>
<div class="line"><a id="l00145" name="l00145"></a><span class="lineno"> 145</span></div>
<div class="line"><a id="l00147" name="l00147"></a><span class="lineno"> 147</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ab38d15e85076ee4300af489ffb27357c">clearReverseVertexQueue</a>();</div>
<div class="line"><a id="l00148" name="l00148"></a><span class="lineno"> 148</span> <span class="keywordtype">void</span> clearForwardVertexQueue();</div>
<div class="line"><a id="l00149" name="l00149"></a><span class="lineno"> 149</span></div>
<div class="line"><a id="l00151" name="l00151"></a><span class="lineno"> 151</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a31ada69a235ff021779d91ed5b64575e">resetReverseValue</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00152" name="l00152"></a><span class="lineno"> 152</span> <span class="keywordtype">void</span> resetForwardValue(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00153" name="l00153"></a><span class="lineno"> 153</span></div>
<div class="line"><a id="l00155" name="l00155"></a><span class="lineno"> 155</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#aed847feacdf233edff43978c29b6acbe">terminateSearch</a>();</div>
<div class="line"><a id="l00156" name="l00156"></a><span class="lineno"> 156</span></div>
<div class="line"><a id="l00158" name="l00158"></a><span class="lineno"> 158</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a7c3537fc249b1bdefd3a9760a87b7bad">insertGoalVerticesInReverseVertexQueue</a>();</div>
<div class="line"><a id="l00159" name="l00159"></a><span class="lineno"> 159</span> <span class="keywordtype">void</span> insertStartVerticesInForWardVertexQueue();</div>
<div class="line"><a id="l00160" name="l00160"></a><span class="lineno"> 160</span></div>
<div class="line"><a id="l00162" name="l00162"></a><span class="lineno"> 162</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a6ea7697e31aa3d9840db76a361ea3068">SelectExpandState</a>(<span class="keywordtype">bool</span> &forward);</div>
<div class="line"><a id="l00163" name="l00163"></a><span class="lineno"> 163</span></div>
<div class="line"><a id="l00165" name="l00165"></a><span class="lineno"> 165</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a67625069894120035c8080468e463306">resetForwardParentInformation</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00166" name="l00166"></a><span class="lineno"> 166</span> <span class="keywordtype">void</span> resetReverseParentInformation(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00167" name="l00167"></a><span class="lineno"> 167</span> <span class="keywordtype">void</span> resetForwardParentAndRemeberTheVertex(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &child,</div>
<div class="line"><a id="l00168" name="l00168"></a><span class="lineno"> 168</span> <span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &parent);</div>
<div class="line"><a id="l00169" name="l00169"></a><span class="lineno"> 169</span> <span class="keywordtype">void</span> resetReverseParentAndRemeberTheVertex(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &child,</div>
<div class="line"><a id="l00170" name="l00170"></a><span class="lineno"> 170</span> <span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &parent);</div>
<div class="line"><a id="l00171" name="l00171"></a><span class="lineno"> 171</span></div>
<div class="line"><a id="l00173" name="l00173"></a><span class="lineno"> 173</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a8a8972b451ced28384b8be0dd17c20e3">lookingForBestNeighbor</a>(<a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> curMin_, <span class="keywordtype">size_t</span> neighbor);</div>
<div class="line"><a id="l00174" name="l00174"></a><span class="lineno"> 174</span> <span class="keywordtype">void</span> bestNeighbor(<a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costToCome, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costToGoal, <span class="keywordtype">size_t</span> neighbor);</div>
<div class="line"><a id="l00175" name="l00175"></a><span class="lineno"> 175</span></div>
<div class="line"><a id="l00177" name="l00177"></a><span class="lineno"> 177</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a4f60a2ac865470afef89290b6bc240c8">ForwardLazySearch</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00178" name="l00178"></a><span class="lineno"> 178</span> <span class="keywordtype">void</span> ReverseLazySearch(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00179" name="l00179"></a><span class="lineno"> 179</span></div>
<div class="line"><a id="l00181" name="l00181"></a><span class="lineno"> 181</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a3cdab289d3704ad43ed6838a85dd0587">PathValidity</a>(std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00182" name="l00182"></a><span class="lineno"> 182</span> <span class="keywordtype">void</span> ForwardPathValidityChecking(std::shared_ptr<blitstar::Vertex> &vertex, <span class="keywordtype">bool</span> &validity);</div>
<div class="line"><a id="l00183" name="l00183"></a><span class="lineno"> 183</span> <span class="keywordtype">void</span> ReversePathValidityChecking(std::shared_ptr<blitstar::Vertex> &vertex, <span class="keywordtype">bool</span> &validity);</div>
<div class="line"><a id="l00184" name="l00184"></a><span class="lineno"> 184</span></div>
<div class="line"><a id="l00186" name="l00186"></a><span class="lineno"> 186</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a7d64e5415b00e3161d4fa42e46452e78">isValidAtResolution</a>(<span class="keyword">const</span> blitstar::keyEdgePair &edge, std::size_t numChecks, <span class="keywordtype">bool</span> sparseCheck);</div>
<div class="line"><a id="l00187" name="l00187"></a><span class="lineno"> 187</span></div>
<div class="line"><a id="l00189" name="l00189"></a><span class="lineno"> 189</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a3163c3669e3d0b1f0b1a93d4e201f2ad">EvaluateValidityStartAndToGoal</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &start,</div>
<div class="line"><a id="l00190" name="l00190"></a><span class="lineno"> 190</span> <span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &goal);</div>
<div class="line"><a id="l00191" name="l00191"></a><span class="lineno"> 191</span></div>
<div class="line"><a id="l00193" name="l00193"></a><span class="lineno"> 193</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#ae719d5e4c68a0daa728303e2700e8361">insertOrUpdateInForwardVertexQueue</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex,</div>
<div class="line"><a id="l00194" name="l00194"></a><span class="lineno"> 194</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToCome, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToGoal,</div>
<div class="line"><a id="l00195" name="l00195"></a><span class="lineno"> 195</span> <span class="keywordtype">bool</span> couldMeet);</div>
<div class="line"><a id="l00196" name="l00196"></a><span class="lineno"> 196</span> <span class="keywordtype">void</span> insertOrUpdateInReverseVertexQueue(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex,</div>
<div class="line"><a id="l00197" name="l00197"></a><span class="lineno"> 197</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToCome, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToGoal,</div>
<div class="line"><a id="l00198" name="l00198"></a><span class="lineno"> 198</span> <span class="keywordtype">bool</span> couldMeet);</div>
<div class="line"><a id="l00199" name="l00199"></a><span class="lineno"> 199</span></div>
<div class="line"><a id="l00201" name="l00201"></a><span class="lineno"> 201</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#a5180d204c57f2674e69a8d57bb52e1d0">updateReverseCost</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costToCome,</div>
<div class="line"><a id="l00202" name="l00202"></a><span class="lineno"> 202</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &costToGo);</div>
<div class="line"><a id="l00203" name="l00203"></a><span class="lineno"> 203</span> <span class="keywordtype">void</span> updateForwardCost(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costToCome,</div>
<div class="line"><a id="l00204" name="l00204"></a><span class="lineno"> 204</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &costToGo);</div>
<div class="line"><a id="l00205" name="l00205"></a><span class="lineno"> 205</span> <span class="keywordtype">void</span> updateCostToGo(<a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &costToCome, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &costToGo,</div>
<div class="line"><a id="l00206" name="l00206"></a><span class="lineno"> 206</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costFromOriginal, <span class="keywordtype">bool</span> meetOnTree);</div>
<div class="line"><a id="l00207" name="l00207"></a><span class="lineno"> 207</span></div>
<div class="line"><a id="l00209" name="l00209"></a><span class="lineno"> 209</span> <span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1BLITstar.html#af6167ef3e464685a27026c66ba0fe34d">updateBestSolutionFoundSoFar</a>(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex,</div>
<div class="line"><a id="l00210" name="l00210"></a><span class="lineno"> 210</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> meetCost, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costToCome,</div>
<div class="line"><a id="l00211" name="l00211"></a><span class="lineno"> 211</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &costToGo, <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> costFromOri);</div>
<div class="line"><a id="l00212" name="l00212"></a><span class="lineno"> 212</span> </div>
<div class="line"><a id="l00213" name="l00213"></a><span class="lineno"> 213</span> <span class="keyword">private</span>:</div>
<div class="line"><a id="l00215" name="l00215"></a><span class="lineno"> 215</span> <span class="keywordtype">void</span> iterate(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a> &terminationCondition);</div>
<div class="line"><a id="l00216" name="l00216"></a><span class="lineno"> 216</span> ompl::base::SpaceInformationPtr spaceInformation_;</div>
<div class="line"><a id="l00217" name="l00217"></a><span class="lineno"> 217</span> </div>
<div class="line"><a id="l00218" name="l00218"></a><span class="lineno"> 218</span> <a class="code hl_class" href="classompl_1_1base_1_1State.html">ompl::base::State</a> *detectionState_;</div>
<div class="line"><a id="l00219" name="l00219"></a><span class="lineno"> 219</span></div>
<div class="line"><a id="l00221" name="l00221"></a><span class="lineno"> 221</span> <span class="keywordtype">void</span> informAboutNewSolution() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00223" name="l00223"></a><span class="lineno"> 223</span> <span class="keywordtype">void</span> informAboutPlannerStatus(<a class="code hl_enumeration" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a> status) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00224" name="l00224"></a><span class="lineno"> 224</span></div>
<div class="line"><a id="l00226" name="l00226"></a><span class="lineno"> 226</span> <span class="keywordtype">void</span> insertGoalVerticesInReverseQueue();</div>
<div class="line"><a id="l00227" name="l00227"></a><span class="lineno"> 227</span></div>
<div class="line"><a id="l00229" name="l00229"></a><span class="lineno"> 229</span> std::shared_ptr<ompl::geometric::PathGeometric></div>
<div class="line"><a id="l00230" name="l00230"></a><span class="lineno"> 230</span> getPathToVertex(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00231" name="l00231"></a><span class="lineno"> 231</span></div>
<div class="line"><a id="l00233" name="l00233"></a><span class="lineno"> 233</span> std::array<ompl::base::Cost, 3u> computeEstimatedPathCosts(<a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToStart,</div>
<div class="line"><a id="l00234" name="l00234"></a><span class="lineno"> 234</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToGoal,</div>
<div class="line"><a id="l00235" name="l00235"></a><span class="lineno"> 235</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> motionCost) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00236" name="l00236"></a><span class="lineno"> 236</span> </div>
<div class="line"><a id="l00237" name="l00237"></a><span class="lineno"> 237</span> std::array<ompl::base::Cost, 3u> computeSortKey(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &parent,</div>
<div class="line"><a id="l00238" name="l00238"></a><span class="lineno"> 238</span> <span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &child) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00239" name="l00239"></a><span class="lineno"> 239</span></div>
<div class="line"><a id="l00241" name="l00241"></a><span class="lineno"> 241</span> std::array<ompl::base::Cost, 2u> computeSortKey(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00242" name="l00242"></a><span class="lineno"> 242</span> </div>
<div class="line"><a id="l00243" name="l00243"></a><span class="lineno"> 243</span> std::array<ompl::base::Cost, 2u> computeEstimatedPathCosts(<a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToStart,</div>
<div class="line"><a id="l00244" name="l00244"></a><span class="lineno"> 244</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> CostToGoal) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00245" name="l00245"></a><span class="lineno"> 245</span></div>
<div class="line"><a id="l00247" name="l00247"></a><span class="lineno"> 247</span> <span class="keywordtype">void</span> updateExactSolution();</div>
<div class="line"><a id="l00248" name="l00248"></a><span class="lineno"> 248</span></div>
<div class="line"><a id="l00250" name="l00250"></a><span class="lineno"> 250</span> <a class="code hl_enumeration" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a> updateSolution();</div>
<div class="line"><a id="l00251" name="l00251"></a><span class="lineno"> 251</span></div>
<div class="line"><a id="l00253" name="l00253"></a><span class="lineno"> 253</span> <a class="code hl_enumeration" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a> updateSolution(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex);</div>
<div class="line"><a id="l00254" name="l00254"></a><span class="lineno"> 254</span></div>
<div class="line"><a id="l00256" name="l00256"></a><span class="lineno"> 256</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> lowerboundToStart(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00258" name="l00258"></a><span class="lineno"> 258</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> lowerboundToGoal(<span class="keyword">const</span> std::shared_ptr<blitstar::Vertex> &vertex) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00259" name="l00259"></a><span class="lineno"> 259</span></div>
<div class="line"><a id="l00261" name="l00261"></a><span class="lineno"> 261</span> std::size_t countNumVerticesInForwardTree() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00262" name="l00262"></a><span class="lineno"> 262</span></div>
<div class="line"><a id="l00264" name="l00264"></a><span class="lineno"> 264</span> std::size_t countNumVerticesInReverseTree() <span class="keyword">const</span>;</div>
<div class="line"><a id="l00265" name="l00265"></a><span class="lineno"> 265</span></div>
<div class="line"><a id="l00267" name="l00267"></a><span class="lineno"> 267</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> solutionCost_;</div>
<div class="line"><a id="l00268" name="l00268"></a><span class="lineno"> 268</span></div>
<div class="line"><a id="l00270" name="l00270"></a><span class="lineno"> 270</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> PriorityC;</div>
<div class="line"><a id="l00271" name="l00271"></a><span class="lineno"> 271</span></div>
<div class="line"><a id="l00273" name="l00273"></a><span class="lineno"> 273</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> C_curr;</div>
<div class="line"><a id="l00274" name="l00274"></a><span class="lineno"> 274</span></div>
<div class="line"><a id="l00276" name="l00276"></a><span class="lineno"> 276</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> approximateSolutionCost_{};</div>
<div class="line"><a id="l00277" name="l00277"></a><span class="lineno"> 277</span></div>
<div class="line"><a id="l00279" name="l00279"></a><span class="lineno"> 279</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> approximateSolutionCostToGoal_{};</div>
<div class="line"><a id="l00280" name="l00280"></a><span class="lineno"> 280</span></div>
<div class="line"><a id="l00282" name="l00282"></a><span class="lineno"> 282</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> fmin_{0u};</div>
<div class="line"><a id="l00283" name="l00283"></a><span class="lineno"> 283</span></div>
<div class="line"><a id="l00285" name="l00285"></a><span class="lineno"> 285</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> ForwardCost{0u};</div>
<div class="line"><a id="l00286" name="l00286"></a><span class="lineno"> 286</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> ReverseCost{0u};</div>
<div class="line"><a id="l00287" name="l00287"></a><span class="lineno"> 287</span> </div>
<div class="line"><a id="l00288" name="l00288"></a><span class="lineno"> 288</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> minimalneighbor_{0u};</div>
<div class="line"><a id="l00290" name="l00290"></a><span class="lineno"> 290</span> <a class="code hl_class" href="classompl_1_1geometric_1_1blitstar_1_1ImplicitGraph.html">blitstar::ImplicitGraph</a> graph_;</div>
<div class="line"><a id="l00291" name="l00291"></a><span class="lineno"> 291</span></div>
<div class="line"><a id="l00293" name="l00293"></a><span class="lineno"> 293</span> blitstar::VertexQueue forwardVertexQueue_;</div>
<div class="line"><a id="l00294" name="l00294"></a><span class="lineno"> 294</span> blitstar::VertexQueue reverseVertexQueue_;</div>
<div class="line"><a id="l00295" name="l00295"></a><span class="lineno"> 295</span></div>
<div class="line"><a id="l00297" name="l00297"></a><span class="lineno"> 297</span> std::shared_ptr<blitstar::Vertex> BestVertex_;</div>
<div class="line"><a id="l00298" name="l00298"></a><span class="lineno"> 298</span></div>
<div class="line"><a id="l00300" name="l00300"></a><span class="lineno"> 300</span> std::shared_ptr<ompl::geometric::PathGeometric> path_;</div>
<div class="line"><a id="l00301" name="l00301"></a><span class="lineno"> 301</span></div>
<div class="line"><a id="l00303" name="l00303"></a><span class="lineno"> 303</span> blitstar::MiddleVertex V_meet;</div>
<div class="line"><a id="l00304" name="l00304"></a><span class="lineno"> 304</span></div>
<div class="line"><a id="l00306" name="l00306"></a><span class="lineno"> 306</span> <span class="keywordtype">bool</span> isVertexBetter(<span class="keyword">const</span> blitstar::KeyVertexPair &lhs, <span class="keyword">const</span> blitstar::KeyVertexPair &rhs) <span class="keyword">const</span>;</div>
<div class="line"><a id="l00307" name="l00307"></a><span class="lineno"> 307</span></div>
<div class="line"><a id="l00309" name="l00309"></a><span class="lineno"> 309</span> std::size_t numIterations_{0u};</div>
<div class="line"><a id="l00310" name="l00310"></a><span class="lineno"> 310</span> std::size_t bestNeighbor_{0u};</div>
<div class="line"><a id="l00311" name="l00311"></a><span class="lineno"> 311</span> std::size_t numSparseCollisionChecksCurrentLevel_{0u};</div>
<div class="line"><a id="l00312" name="l00312"></a><span class="lineno"> 312</span></div>
<div class="line"><a id="l00314" name="l00314"></a><span class="lineno"> 314</span> std::size_t forwardId_{0u};</div>
<div class="line"><a id="l00315" name="l00315"></a><span class="lineno"> 315</span> std::size_t reverseId_{0u};</div>
<div class="line"><a id="l00316" name="l00316"></a><span class="lineno"> 316</span> </div>
<div class="line"><a id="l00317" name="l00317"></a><span class="lineno"> 317</span> std::size_t meetId_{0u};</div>
<div class="line"><a id="l00319" name="l00319"></a><span class="lineno"> 319</span> std::size_t batchSize_{100u};</div>
<div class="line"><a id="l00320" name="l00320"></a><span class="lineno"> 320</span></div>
<div class="line"><a id="l00322" name="l00322"></a><span class="lineno"> 322</span> <span class="keywordtype">bool</span> trackApproximateSolutions_{<span class="keyword">true</span>};</div>
<div class="line"><a id="l00323" name="l00323"></a><span class="lineno"> 323</span></div>
<div class="line"><a id="l00325" name="l00325"></a><span class="lineno"> 325</span> <span class="keywordtype">bool</span> isPruningEnabled_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00326" name="l00326"></a><span class="lineno"> 326</span> <span class="keywordtype">bool</span> increProcess_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00327" name="l00327"></a><span class="lineno"> 327</span> </div>
<div class="line"><a id="l00328" name="l00328"></a><span class="lineno"> 328</span> <span class="keywordtype">bool</span> meeting_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00329" name="l00329"></a><span class="lineno"> 329</span> <span class="keywordtype">bool</span> start_scratch_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00330" name="l00330"></a><span class="lineno"> 330</span> </div>
<div class="line"><a id="l00331" name="l00331"></a><span class="lineno"> 331</span> <span class="keywordtype">bool</span> betterThan(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &cost1, <span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &cost2);</div>
<div class="line"><a id="l00332" name="l00332"></a><span class="lineno"> 332</span> <span class="keywordtype">bool</span> largerThan(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &cost1, <span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> &cost2);</div>
<div class="line"><a id="l00333" name="l00333"></a><span class="lineno"> 333</span></div>
<div class="line"><a id="l00335" name="l00335"></a><span class="lineno"> 335</span> <span class="keywordtype">bool</span> NeedMoreSamples();</div>
<div class="line"><a id="l00336" name="l00336"></a><span class="lineno"> 336</span> <span class="keywordtype">bool</span> iSolution_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00337" name="l00337"></a><span class="lineno"> 337</span> <span class="keywordtype">bool</span> need_Prune_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00338" name="l00338"></a><span class="lineno"> 338</span> <span class="keywordtype">bool</span> isVertexEmpty_{<span class="keyword">true</span>};</div>
<div class="line"><a id="l00339" name="l00339"></a><span class="lineno"> 339</span> <span class="keywordtype">bool</span> found_meeting_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00340" name="l00340"></a><span class="lineno"> 340</span> <span class="keywordtype">bool</span> find_solution_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00341" name="l00341"></a><span class="lineno"> 341</span> <span class="keywordtype">bool</span> forwardInvalid_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00342" name="l00342"></a><span class="lineno"> 342</span> <span class="keywordtype">bool</span> reverseInvalid_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00343" name="l00343"></a><span class="lineno"> 343</span> <span class="keywordtype">bool</span> goalCloseToStart_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00344" name="l00344"></a><span class="lineno"> 344</span> <span class="keywordtype">bool</span> searchExhausted_{<span class="keyword">false</span>};</div>
<div class="line"><a id="l00345" name="l00345"></a><span class="lineno"> 345</span> </div>
<div class="line"><a id="l00346" name="l00346"></a><span class="lineno"> 346</span> <span class="keywordtype">double</span> time_taken{0u};</div>
<div class="line"><a id="l00348" name="l00348"></a><span class="lineno"> 348</span> ompl::base::OptimizationObjectivePtr objective_;</div>
<div class="line"><a id="l00349" name="l00349"></a><span class="lineno"> 349</span></div>
<div class="line"><a id="l00351" name="l00351"></a><span class="lineno"> 351</span> ompl::base::MotionValidatorPtr motionValidator_;</div>
<div class="line"><a id="l00352" name="l00352"></a><span class="lineno"> 352</span></div>
<div class="line"><a id="l00354" name="l00354"></a><span class="lineno"> 354</span> std::size_t numProcessedEdges_{0u};</div>
<div class="line"><a id="l00355" name="l00355"></a><span class="lineno"> 355</span> std::size_t numbatch_{0u};</div>
<div class="line"><a id="l00356" name="l00356"></a><span class="lineno"> 356</span> std::shared_ptr<ompl::base::StateSpace> space_;</div>
<div class="line"><a id="l00358" name="l00358"></a><span class="lineno"> 358</span> std::size_t numEdgeCollisionChecks_{0u};</div>
<div class="line"><a id="l00359" name="l00359"></a><span class="lineno"> 359</span></div>
<div class="line"><a id="l00361" name="l00361"></a><span class="lineno"> 361</span> <span class="keyword">mutable</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> numCollisionCheckedEdges_{0u};</div>
<div class="line"><a id="l00362" name="l00362"></a><span class="lineno"> 362</span> };</div>
</div>
<div class="line"><a id="l00363" name="l00363"></a><span class="lineno"> 363</span> } <span class="comment">// namespace geometric</span></div>
<div class="line"><a id="l00364" name="l00364"></a><span class="lineno"> 364</span>} <span class="comment">// namespace ompl</span></div>
<div class="line"><a id="l00365" name="l00365"></a><span class="lineno"> 365</span> </div>
<div class="line"><a id="l00366" name="l00366"></a><span class="lineno"> 366</span><span class="preprocessor">#endif </span><span class="comment">// OMPL_GEOMETRIC_PLANNERS_INFORMEDTREES_bmitstar</span></div>
<div class="ttc" id="aclassompl_1_1base_1_1Cost_html"><div class="ttname"><a href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a></div><div class="ttdoc">Definition of a cost value. Can represent the cost of a motion or the cost of a state.</div><div class="ttdef"><b>Definition</b> <a href="Cost_8h_source.html#l00047">Cost.h:48</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html">ompl::base::PlannerData</a></div><div class="ttdoc">Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...</div><div class="ttdef"><b>Definition</b> <a href="base_2PlannerData_8h_source.html#l00174">PlannerData.h:175</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerTerminationCondition_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a></div><div class="ttdoc">Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...</div><div class="ttdef"><b>Definition</b> <a href="PlannerTerminationCondition_8h_source.html#l00063">PlannerTerminationCondition.h:64</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html">ompl::base::Planner</a></div><div class="ttdoc">Base class for a planner.</div><div class="ttdef"><b>Definition</b> <a href="Planner_8h_source.html#l00215">Planner.h:216</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1State_html"><div class="ttname"><a href="classompl_1_1base_1_1State.html">ompl::base::State</a></div><div class="ttdoc">Definition of an abstract state.</div><div class="ttdef"><b>Definition</b> <a href="base_2State_8h_source.html#l00049">State.h:50</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a18d32dba4d2dd41af3f356a6170b08da"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a18d32dba4d2dd41af3f356a6170b08da">ompl::geometric::BLITstar::getUseKNearest</a></div><div class="ttdeci">bool getUseKNearest() const</div><div class="ttdoc">Get whether to use a k-nearest RGG connection model. If false, BLIT* uses an r-disc model.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00343">BLITstar.cpp:343</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a20acf9a45d6b214587a36d401b7db7fd"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a20acf9a45d6b214587a36d401b7db7fd">ompl::geometric::BLITstar::solve</a></div><div class="ttdeci">ompl::base::PlannerStatus solve(const ompl::base::PlannerTerminationCondition &terminationCondition) override</div><div class="ttdoc">Solves a motion planning problem.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00227">BLITstar.cpp:227</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a28a1aeb65335f8f50d71645903b132fa"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a28a1aeb65335f8f50d71645903b132fa">ompl::geometric::BLITstar::enablePruning</a></div><div class="ttdeci">void enablePruning(bool prune)</div><div class="ttdoc">Set whether pruning is enabled or not.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00328">BLITstar.cpp:328</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a2e11939b4f5d06d743f03207e4059bb7"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a2e11939b4f5d06d743f03207e4059bb7">ompl::geometric::BLITstar::setup</a></div><div class="ttdeci">void setup() override</div><div class="ttdoc">Additional setup that can only be done once a problem definition is set.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00108">BLITstar.cpp:108</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a3163c3669e3d0b1f0b1a93d4e201f2ad"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a3163c3669e3d0b1f0b1a93d4e201f2ad">ompl::geometric::BLITstar::EvaluateValidityStartAndToGoal</a></div><div class="ttdeci">void EvaluateValidityStartAndToGoal(const std::shared_ptr< blitstar::Vertex > &start, const std::shared_ptr< blitstar::Vertex > &goal)</div><div class="ttdoc">Checking the collision detection between start and goal vertices.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01088">BLITstar.cpp:1088</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a31ada69a235ff021779d91ed5b64575e"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a31ada69a235ff021779d91ed5b64575e">ompl::geometric::BLITstar::resetReverseValue</a></div><div class="ttdeci">void resetReverseValue(const std::shared_ptr< blitstar::Vertex > &vertex)</div><div class="ttdoc">Reset a vertex's value.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00681">BLITstar.cpp:681</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a3cdab289d3704ad43ed6838a85dd0587"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a3cdab289d3704ad43ed6838a85dd0587">ompl::geometric::BLITstar::PathValidity</a></div><div class="ttdeci">bool PathValidity(std::shared_ptr< blitstar::Vertex > &vertex)</div><div class="ttdoc">Checking the validity of a path from each direction.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00574">BLITstar.cpp:574</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a474a2063cc0bc73afd8f30108bde8fa8"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a474a2063cc0bc73afd8f30108bde8fa8">ompl::geometric::BLITstar::isPruningEnabled</a></div><div class="ttdeci">bool isPruningEnabled() const</div><div class="ttdoc">Get whether pruning is enabled or not.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00333">BLITstar.cpp:333</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a4f60a2ac865470afef89290b6bc240c8"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a4f60a2ac865470afef89290b6bc240c8">ompl::geometric::BLITstar::ForwardLazySearch</a></div><div class="ttdeci">void ForwardLazySearch(const std::shared_ptr< blitstar::Vertex > &vertex)</div><div class="ttdoc">Forward and Reverse Search.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00794">BLITstar.cpp:794</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a5180d204c57f2674e69a8d57bb52e1d0"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a5180d204c57f2674e69a8d57bb52e1d0">ompl::geometric::BLITstar::updateReverseCost</a></div><div class="ttdeci">void updateReverseCost(const std::shared_ptr< blitstar::Vertex > &vertex, ompl::base::Cost costToCome, ompl::base::Cost &costToGo)</div><div class="ttdoc">Refine heuristics on-the-fly.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01063">BLITstar.cpp:1063</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a65f06eb63257965203f381ef006d4a6c"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a65f06eb63257965203f381ef006d4a6c">ompl::geometric::BLITstar::setUseKNearest</a></div><div class="ttdeci">void setUseKNearest(bool useKNearest)</div><div class="ttdoc">Set whether to use a k-nearest RGG connection model. If false, BLIT* uses an r-disc model.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00338">BLITstar.cpp:338</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a662354a31a8627a4684c17e58fdc555e"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a662354a31a8627a4684c17e58fdc555e">ompl::geometric::BLITstar::clear</a></div><div class="ttdeci">void clear() override</div><div class="ttdoc">Clears the algorithm's internal state.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00218">BLITstar.cpp:218</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a67625069894120035c8080468e463306"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a67625069894120035c8080468e463306">ompl::geometric::BLITstar::resetForwardParentInformation</a></div><div class="ttdeci">void resetForwardParentInformation(const std::shared_ptr< blitstar::Vertex > &vertex)</div><div class="ttdoc">Reset parent vertex's information.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00652">BLITstar.cpp:652</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a6ea7697e31aa3d9840db76a361ea3068"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a6ea7697e31aa3d9840db76a361ea3068">ompl::geometric::BLITstar::SelectExpandState</a></div><div class="ttdeci">bool SelectExpandState(bool &forward)</div><div class="ttdoc">Select the vertex with minimal priority on both trees.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01407">BLITstar.cpp:1407</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a79d38cea98702a653e6aa479b9761ab2"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a79d38cea98702a653e6aa479b9761ab2">ompl::geometric::BLITstar::getMaxNumberOfGoals</a></div><div class="ttdeci">unsigned int getMaxNumberOfGoals() const</div><div class="ttdoc">Get the maximum number of goals BLIT* will sample from sampleable goal regions.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00353">BLITstar.cpp:353</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a7c3537fc249b1bdefd3a9760a87b7bad"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a7c3537fc249b1bdefd3a9760a87b7bad">ompl::geometric::BLITstar::insertGoalVerticesInReverseVertexQueue</a></div><div class="ttdeci">void insertGoalVerticesInReverseVertexQueue()</div><div class="ttdoc">Insert start and goal vertices into the queues.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00512">BLITstar.cpp:512</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a7d64e5415b00e3161d4fa42e46452e78"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a7d64e5415b00e3161d4fa42e46452e78">ompl::geometric::BLITstar::isValidAtResolution</a></div><div class="ttdeci">bool isValidAtResolution(const blitstar::keyEdgePair &edge, std::size_t numChecks, bool sparseCheck)</div><div class="ttdoc">Checking the collision detection.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01480">BLITstar.cpp:1480</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a89f1a931b36ffe3dc90783e085ba5595"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a89f1a931b36ffe3dc90783e085ba5595">ompl::geometric::BLITstar::ensureStartAndGoalStates</a></div><div class="ttdeci">ompl::base::PlannerStatus::StatusType ensureStartAndGoalStates(const ompl::base::PlannerTerminationCondition &terminationCondition)</div><div class="ttdoc">Checks whether the problem is successfully setup.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00186">BLITstar.cpp:186</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a8a8972b451ced28384b8be0dd17c20e3"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a8a8972b451ced28384b8be0dd17c20e3">ompl::geometric::BLITstar::lookingForBestNeighbor</a></div><div class="ttdeci">void lookingForBestNeighbor(ompl::base::Cost curMin_, size_t neighbor)</div><div class="ttdoc">Look for a neighbor with the minimal priority.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00532">BLITstar.cpp:532</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a95d166539f25ef236d39406edf3bdb65"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a95d166539f25ef236d39406edf3bdb65">ompl::geometric::BLITstar::getBatchSize</a></div><div class="ttdeci">std::size_t getBatchSize() const</div><div class="ttdoc">Get the batch size.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00313">BLITstar.cpp:313</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a999619bb38cc4cf2ae7c5caabdcdcdbc"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a999619bb38cc4cf2ae7c5caabdcdcdbc">ompl::geometric::BLITstar::setBatchSize</a></div><div class="ttdeci">void setBatchSize(std::size_t batchSize)</div><div class="ttdoc">Set the batch size.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00308">BLITstar.cpp:308</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_a9fcdc97efcbe88a6168ef781f882c752"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#a9fcdc97efcbe88a6168ef781f882c752">ompl::geometric::BLITstar::BLITstar</a></div><div class="ttdeci">BLITstar(const ompl::base::SpaceInformationPtr &spaceInformation)</div><div class="ttdoc">Constructs a BLIT*.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00064">BLITstar.cpp:64</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_aa591f363bc895fee624dcf0ca68417ec"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#aa591f363bc895fee624dcf0ca68417ec">ompl::geometric::BLITstar::SCD</a></div><div class="ttdeci">bool SCD(const blitstar::keyEdgePair &edge)</div><div class="ttdoc">Above references inherit from BLIT*.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01469">BLITstar.cpp:1469</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ab38d15e85076ee4300af489ffb27357c"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ab38d15e85076ee4300af489ffb27357c">ompl::geometric::BLITstar::clearReverseVertexQueue</a></div><div class="ttdeci">void clearReverseVertexQueue()</div><div class="ttdoc">Empty the queues.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00358">BLITstar.cpp:358</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ab81f56c18cf2d198785da5f0c225cafe"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ab81f56c18cf2d198785da5f0c225cafe">ompl::geometric::BLITstar::getRewireFactor</a></div><div class="ttdeci">double getRewireFactor() const</div><div class="ttdoc">Get the rewire factor of the RGG graph.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00323">BLITstar.cpp:323</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_abfdb2d59132d25abd2b5dd33b437def9"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#abfdb2d59132d25abd2b5dd33b437def9">ompl::geometric::BLITstar::getPlannerData</a></div><div class="ttdeci">void getPlannerData(base::PlannerData &data) const override</div><div class="ttdoc">Get the planner data.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00264">BLITstar.cpp:264</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ac65310d23b7d78195f88094f1483a3e9"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ac65310d23b7d78195f88094f1483a3e9">ompl::geometric::BLITstar::setMaxNumberOfGoals</a></div><div class="ttdeci">void setMaxNumberOfGoals(unsigned int numberOfGoals)</div><div class="ttdoc">Set the maximum number of goals BLIT* will sample from sampleable goal regions.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00348">BLITstar.cpp:348</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ac86620e8396f059553c2194e5b1793a4"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ac86620e8396f059553c2194e5b1793a4">ompl::geometric::BLITstar::setRewireFactor</a></div><div class="ttdeci">void setRewireFactor(double rewireFactor)</div><div class="ttdoc">Set the rewire factor of the RGG graph.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00318">BLITstar.cpp:318</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ad7ca75689a41846bbf0c9f7647dcca3a"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ad7ca75689a41846bbf0c9f7647dcca3a">ompl::geometric::BLITstar::ensureSetup</a></div><div class="ttdeci">ompl::base::PlannerStatus::StatusType ensureSetup()</div><div class="ttdoc">Checks whether the planner is successfully setup.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00162">BLITstar.cpp:162</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_ae719d5e4c68a0daa728303e2700e8361"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#ae719d5e4c68a0daa728303e2700e8361">ompl::geometric::BLITstar::insertOrUpdateInForwardVertexQueue</a></div><div class="ttdeci">void insertOrUpdateInForwardVertexQueue(const std::shared_ptr< blitstar::Vertex > &vertex, ompl::base::Cost CostToCome, ompl::base::Cost CostToGoal, bool couldMeet)</div><div class="ttdoc">Inserts or updates a vertex in the reverse queue.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01284">BLITstar.cpp:1284</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_aed847feacdf233edff43978c29b6acbe"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#aed847feacdf233edff43978c29b6acbe">ompl::geometric::BLITstar::terminateSearch</a></div><div class="ttdeci">bool terminateSearch()</div><div class="ttdoc">Ensuring meet-in-the-middle and optimality to terminate the current search.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00697">BLITstar.cpp:697</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_af24abbf20d6e3b838864b44803be7496"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#af24abbf20d6e3b838864b44803be7496">ompl::geometric::BLITstar::~BLITstar</a></div><div class="ttdeci">~BLITstar()</div><div class="ttdoc">Destructs a BLIT*.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l00103">BLITstar.cpp:103</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BLITstar_html_af6167ef3e464685a27026c66ba0fe34d"><div class="ttname"><a href="classompl_1_1geometric_1_1BLITstar.html#af6167ef3e464685a27026c66ba0fe34d">ompl::geometric::BLITstar::updateBestSolutionFoundSoFar</a></div><div class="ttdeci">void updateBestSolutionFoundSoFar(const std::shared_ptr< blitstar::Vertex > &vertex, ompl::base::Cost meetCost, ompl::base::Cost costToCome, ompl::base::Cost &costToGo, ompl::base::Cost costFromOri)</div><div class="ttdoc">Improve the current solution.</div><div class="ttdef"><b>Definition</b> <a href="BLITstar_8cpp_source.html#l01013">BLITstar.cpp:1013</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1blitstar_1_1ImplicitGraph_html"><div class="ttname"><a href="classompl_1_1geometric_1_1blitstar_1_1ImplicitGraph.html">ompl::geometric::blitstar::ImplicitGraph</a></div><div class="ttdef"><b>Definition</b> <a href="lazyinformedtrees_2blitstar_2ImplicitGraph_8h_source.html#l00066">ImplicitGraph.h:67</a></div></div>
<div class="ttc" id="anamespaceompl_1_1geometric_html"><div class="ttname"><a href="namespaceompl_1_1geometric.html">ompl::geometric</a></div><div class="ttdoc">This namespace contains code that is specific to planning under geometric constraints.</div><div class="ttdef"><b>Definition</b> <a href="GeneticSearch_8h_source.html#l00047">GeneticSearch.h:48</a></div></div>
<div class="ttc" id="anamespaceompl_html"><div class="ttname"><a href="namespaceompl.html">ompl</a></div><div class="ttdoc">Main namespace. Contains everything in this library.</div><div class="ttdef"><b>Definition</b> <a href="MultiLevelPlanarManipulatorDemo_8cpp_source.html#l00065">MultiLevelPlanarManipulatorDemo.cpp:66</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a></div><div class="ttdoc">A class to store the exit status of Planner::solve().</div><div class="ttdef"><b>Definition</b> <a href="PlannerStatus_8h_source.html#l00048">PlannerStatus.h:49</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a></div><div class="ttdeci">StatusType</div><div class="ttdoc">The possible values of the status returned by a planner.</div><div class="ttdef"><b>Definition</b> <a href="PlannerStatus_8h_source.html#l00051">PlannerStatus.h:52</a></div></div>
</div><!-- fragment --></div><!-- contents -->
</div>
<footer class="footer">
<div class="container">
<a href="http://www.kavrakilab.org">Kavraki Lab</a> •
<a href="https://www.cs.rice.edu">Department of Computer Science</a> •
<a href="https://www.rice.edu">Rice University</a><br/>
Funded in part by the <a href="https://www.nsf.gov">National Science Foundation</a><br/>
Documentation generated by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.16.1
</div>
</footer>
<script>
(function(i,s,o,g,r,a,m){i['GoogleAnalyticsObject']=r;i[r]=i[r]||function(){
(i[r].q=i[r].q||[]).push(arguments)},i[r].l=1*new Date();a=s.createElement(o),
m=s.getElementsByTagName(o)[0];a.async=1;a.src=g;m.parentNode.insertBefore(a,m)
})(window,document,'script','//www.google-analytics.com/analytics.js','ga');
ga('create', 'UA-9156598-2', 'auto');
ga('send', 'pageview');
</script>
<script src="https://cdnjs.cloudflare.com/ajax/libs/popper.js/1.14.7/umd/popper.min.js" integrity="sha384-UO2eT0CpHqdSJQ6hJty5KVphtPhzWj9WO1clHTMGa3JDZwrnQq4sF86dIHNDz0W1" crossorigin="anonymous"></script>
<script src="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/js/bootstrap.min.js" integrity="sha384-JjSmVgyd0p3pXB1rRibZUAYoIIy6OrQ6VrjIEaFf/nJGzIxFDsf4x0xIM+B07jRM" crossorigin="anonymous"></script>
</body>
</html>