-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathBKPIECE1_8cpp_source.html
480 lines (478 loc) · 75.1 KB
/
BKPIECE1_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
<!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/kpiece/src/BKPIECE1.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_8563ad9cc395af0250a1edc99fdc12b7.html">kpiece</a></li><li class="navelem"><a class="el" href="dir_d5d5069e66b5055e3920724a25b4f628.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">BKPIECE1.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) 2011, Rice University,</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 Rice University 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">/* Author: Ioan Sucan */</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/kpiece/BKPIECE1.h"</span></div>
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span> <span class="preprocessor">#include "ompl/base/goals/GoalSampleableRegion.h"</span></div>
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="preprocessor">#include "ompl/tools/config/SelfConfig.h"</span></div>
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span> <span class="preprocessor">#include <cassert></span></div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span>  </div>
<div class="line"><a name="l00042"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#a1e61534ba2f912016e00d94cfc5449e5"> 42</a></span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a1e61534ba2f912016e00d94cfc5449e5">ompl::geometric::BKPIECE1::BKPIECE1</a>(<span class="keyword">const</span> base::SpaceInformationPtr &si)</div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span>  : base::Planner(si, <span class="stringliteral">"BKPIECE1"</span>)</div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  , dStart_([this](<a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> *m) { <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#ae81ac9338565790508efaebbef3d8459">freeMotion</a>(m); })</div>
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span>  , dGoal_([<span class="keyword">this</span>](Motion *m) { freeMotion(m); })</div>
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span> {</div>
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span>  specs_.recognizedGoal = <a class="code" href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55a6fb685fa51055688c4e130094225b7f9">base::GOAL_SAMPLEABLE_REGION</a>;</div>
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span>  </div>
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span>  Planner::declareParam<double>(<span class="stringliteral">"range"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#ab803b4859de12fd5788e87b99c672679">BKPIECE1::setRange</a>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#ad01e749cab8b9096d01e8f9f3ca35f61">BKPIECE1::getRange</a>, <span class="stringliteral">"0.:1.:10000."</span>);</div>
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span>  Planner::declareParam<double>(<span class="stringliteral">"border_fraction"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a57e4e557bbd43543c4fe5d5d3733b443">BKPIECE1::setBorderFraction</a>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a6dd67ede6c67a142ff0270ec91b3a2d4">BKPIECE1::getBorderFraction</a>,</div>
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span>  <span class="stringliteral">"0.:.05:1."</span>);</div>
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  Planner::declareParam<double>(<span class="stringliteral">"failed_expansion_score_factor"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a06f49930fd458b8ff60626a1f0b1b775">BKPIECE1::setFailedExpansionCellScoreFactor</a>,</div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span>  &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#af93f42bd3ebf86547cfcb61ab1280e99">BKPIECE1::getFailedExpansionCellScoreFactor</a>);</div>
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span>  Planner::declareParam<double>(<span class="stringliteral">"min_valid_path_fraction"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a1cc89cb07e13a333f6eed645a3dfcda3">BKPIECE1::setMinValidPathFraction</a>,</div>
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  &<a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a1cec5e62c6aff0aea1ffef10337c0eb1">BKPIECE1::getMinValidPathFraction</a>);</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>  </div>
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span> ompl::geometric::BKPIECE1::~BKPIECE1() = <span class="keywordflow">default</span>;</div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span>  </div>
<div class="line"><a name="l00060"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#aa724226c3dec34b09cfa9a57e94b4679"> 60</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#aa724226c3dec34b09cfa9a57e94b4679">ompl::geometric::BKPIECE1::setup</a>()</div>
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span> {</div>
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  Planner::setup();</div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  <a class="code" href="classompl_1_1tools_1_1SelfConfig.html">tools::SelfConfig</a> sc(si_, getName());</div>
<div class="line"><a name="l00064"></a><span class="lineno"> 64</span>  sc.<a class="code" href="classompl_1_1tools_1_1SelfConfig.html#a6af441eace888354bcc5afe172561d62">configureProjectionEvaluator</a>(projectionEvaluator_);</div>
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  sc.<a class="code" href="classompl_1_1tools_1_1SelfConfig.html#a65bff53ea4bc6f158342a856175ab9a6">configurePlannerRange</a>(maxDistance_);</div>
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span>  </div>
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  <span class="keywordflow">if</span> (failedExpansionScoreFactor_ < std::numeric_limits<double>::epsilon() || failedExpansionScoreFactor_ > 1.0)</div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">Exception</a>(<span class="stringliteral">"Failed expansion cell score factor must be in the range (0,1]"</span>);</div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  <span class="keywordflow">if</span> (minValidPathFraction_ < std::numeric_limits<double>::epsilon() || minValidPathFraction_ > 1.0)</div>
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span>  <span class="keywordflow">throw</span> <a class="code" href="classompl_1_1Exception.html">Exception</a>(<span class="stringliteral">"The minimum valid path fraction must be in the range (0,1]"</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>  dStart_.setDimension(projectionEvaluator_->getDimension());</div>
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  dGoal_.setDimension(projectionEvaluator_->getDimension());</div>
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span> }</div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  </div>
<div class="line"><a name="l00076"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#a2cf588b5cd49be01cc43c576794c499c"> 76</a></span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a2cf588b5cd49be01cc43c576794c499c">ompl::geometric::BKPIECE1::solve</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span> {</div>
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  checkValidity();</div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  <span class="keyword">auto</span> *goal = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *<span class="keyword">></span>(pdef_->getGoal().get());</div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  </div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  <span class="keywordflow">if</span> (goal == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  {</div>
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Unknown type of goal"</span>, getName().c_str());</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a47d769205044efa345184a640bd863ff">base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE</a>;</div>
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  }</div>
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span>  </div>
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  <a class="code" href="classompl_1_1geometric_1_1Discretization.html#a2dac26349b7da7fe428522518dfea7dc">Discretization<Motion>::Coord</a> xcoord(projectionEvaluator_->getDimension());</div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  </div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *st = pis_.nextStart())</div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  {</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  si_->copyState(motion->state, st);</div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  motion->root = motion->state;</div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  projectionEvaluator_->computeCoordinates(motion->state, xcoord);</div>
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span>  dStart_.addMotion(motion, xcoord);</div>
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  }</div>
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  </div>
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  <span class="keywordflow">if</span> (dStart_.getMotionCount() == 0)</div>
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  {</div>
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Motion planning start tree could not be initialized!"</span>, getName().c_str());</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a1f20d012b563fc223902e24a8bcd7547">base::PlannerStatus::INVALID_START</a>;</div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  }</div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  </div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  <span class="keywordflow">if</span> (!goal->couldSample())</div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  {</div>
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Insufficient states in sampleable goal region"</span>, getName().c_str());</div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  <span class="keywordflow">return</span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a2e2b2b7e02900c4417af0ecea272c637">base::PlannerStatus::INVALID_GOAL</a>;</div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  }</div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  </div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  <span class="keywordflow">if</span> (!sampler_)</div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  sampler_ = si_->allocValidStateSampler();</div>
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  </div>
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Starting planning with %d states already in datastructure"</span>, getName().c_str(),</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  (<span class="keywordtype">int</span>)(dStart_.getMotionCount() + dGoal_.getMotionCount()));</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>  std::vector<Motion *> solution;</div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *xstate = si_->allocState();</div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  <span class="keywordtype">bool</span> startTree = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  <span class="keywordtype">bool</span> solved = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span>  </div>
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span>  <span class="keywordflow">while</span> (!ptc)</div>
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span>  {</div>
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span>  <a class="code" href="classompl_1_1geometric_1_1Discretization.html">Discretization<Motion></a> &disc = startTree ? dStart_ : dGoal_;</div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  startTree = !startTree;</div>
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span>  <a class="code" href="classompl_1_1geometric_1_1Discretization.html">Discretization<Motion></a> &otherDisc = startTree ? dStart_ : dGoal_;</div>
<div class="line"><a name="l00126"></a><span class="lineno"> 126</span>  disc.countIteration();</div>
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  </div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="comment">// if we have not sampled too many goals already</span></div>
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  <span class="keywordflow">if</span> (dGoal_.getMotionCount() == 0 || pis_.getSampledGoalsCount() < dGoal_.getMotionCount() / 2)</div>
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span>  {</div>
<div class="line"><a name="l00131"></a><span class="lineno"> 131</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *st = dGoal_.getMotionCount() == 0 ? pis_.nextGoal(ptc) : pis_.nextGoal();</div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span>  <span class="keywordflow">if</span> (st != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span>  {</div>
<div class="line"><a name="l00134"></a><span class="lineno"> 134</span>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span>  si_->copyState(motion->state, st);</div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span>  motion->root = motion->state;</div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span>  projectionEvaluator_->computeCoordinates(motion->state, xcoord);</div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  dGoal_.addMotion(motion, xcoord);</div>
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span>  }</div>
<div class="line"><a name="l00140"></a><span class="lineno"> 140</span>  <span class="keywordflow">if</span> (dGoal_.getMotionCount() == 0)</div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span>  {</div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Unable to sample any valid states for goal tree"</span>, getName().c_str());</div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  }</div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span>  }</div>
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span>  </div>
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span>  <a class="code" href="classompl_1_1geometric_1_1Discretization.html#a86c80c67138c62e3da31dc5e42e0726b">Discretization<Motion>::Cell</a> *ecell = <span class="keyword">nullptr</span>;</div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  <a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> *existing = <span class="keyword">nullptr</span>;</div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  disc.<a class="code" href="classompl_1_1geometric_1_1Discretization.html#a8db183fa4a3231509336ffb7057805df">selectMotion</a>(existing, ecell);</div>
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span>  assert(existing);</div>
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span>  <span class="keywordflow">if</span> (sampler_->sampleNear(xstate, existing-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>, maxDistance_))</div>
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span>  {</div>
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span>  std::pair<base::State *, double> fail(xstate, 0.0);</div>
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span>  <span class="keywordtype">bool</span> keep = si_->checkMotion(existing-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>, xstate, fail);</div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span>  <span class="keywordflow">if</span> (!keep && fail.second > minValidPathFraction_)</div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span>  keep = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00157"></a><span class="lineno"> 157</span>  </div>
<div class="line"><a name="l00158"></a><span class="lineno"> 158</span>  <span class="keywordflow">if</span> (keep)</div>
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span>  {</div>
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span>  <span class="comment">/* create a motion */</span></div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span>  si_->copyState(motion->state, xstate);</div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  motion->root = existing-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#ab658fee6c2727e70f145252ec4df86c6">root</a>;</div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span>  motion->parent = existing;</div>
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span>  </div>
<div class="line"><a name="l00166"></a><span class="lineno"> 166</span>  projectionEvaluator_->computeCoordinates(motion->state, xcoord);</div>
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  disc.<a class="code" href="classompl_1_1geometric_1_1Discretization.html#a6ac71e099d8a69dc6c2ee5ff1736a277">addMotion</a>(motion, xcoord);</div>
<div class="line"><a name="l00168"></a><span class="lineno"> 168</span>  </div>
<div class="line"><a name="l00169"></a><span class="lineno"> 169</span>  <a class="code" href="classompl_1_1geometric_1_1Discretization.html#a86c80c67138c62e3da31dc5e42e0726b">Discretization<Motion>::Cell</a> *cellC = otherDisc.getGrid().getCell(xcoord);</div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  </div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  <span class="keywordflow">if</span> ((cellC != <span class="keyword">nullptr</span>) && !cellC->data->motions.empty())</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>  <a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> *connectOther = cellC->data->motions[rng_.uniformInt(0, cellC->data->motions.size() - 1)];</div>
<div class="line"><a name="l00174"></a><span class="lineno"> 174</span>  </div>
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  <span class="keywordflow">if</span> (goal->isStartGoalPairValid(startTree ? connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#ab658fee6c2727e70f145252ec4df86c6">root</a> : motion->root,</div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  startTree ? motion->root : connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#ab658fee6c2727e70f145252ec4df86c6">root</a>) &&</div>
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  si_->checkMotion(motion->state, connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>))</div>
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  {</div>
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  <span class="keywordflow">if</span> (startTree)</div>
<div class="line"><a name="l00180"></a><span class="lineno"> 180</span>  connectionPoint_ = std::make_pair(connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>, motion->state);</div>
<div class="line"><a name="l00181"></a><span class="lineno"> 181</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  connectionPoint_ = std::make_pair(motion->state, connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>);</div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span>  </div>
<div class="line"><a name="l00184"></a><span class="lineno"> 184</span>  <span class="comment">/* extract the motions and put them in solution vector */</span></div>
<div class="line"><a name="l00185"></a><span class="lineno"> 185</span>  </div>
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span>  std::vector<Motion *> mpath1;</div>
<div class="line"><a name="l00187"></a><span class="lineno"> 187</span>  <span class="keywordflow">while</span> (motion != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  {</div>
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  mpath1.push_back(motion);</div>
<div class="line"><a name="l00190"></a><span class="lineno"> 190</span>  motion = motion->parent;</div>
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  }</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>  std::vector<Motion *> mpath2;</div>
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  <span class="keywordflow">while</span> (connectOther != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  {</div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  mpath2.push_back(connectOther);</div>
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  connectOther = connectOther-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a31d66a709c8a16e44787f019c9fc13b2">parent</a>;</div>
<div class="line"><a name="l00198"></a><span class="lineno"> 198</span>  }</div>
<div class="line"><a name="l00199"></a><span class="lineno"> 199</span>  </div>
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span>  <span class="keywordflow">if</span> (startTree)</div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  mpath1.swap(mpath2);</div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  </div>
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  <span class="keyword">auto</span> path(std::make_shared<PathGeometric>(si_));</div>
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  path->getStates().reserve(mpath1.size() + mpath2.size());</div>
<div class="line"><a name="l00205"></a><span class="lineno"> 205</span>  <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath1.size() - 1; i >= 0; --i)</div>
<div class="line"><a name="l00206"></a><span class="lineno"> 206</span>  path->append(mpath1[i]->state);</div>
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &i : mpath2)</div>
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  path->append(i->state);</div>
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  </div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  pdef_->addSolutionPath(path, <span class="keyword">false</span>, 0.0, getName());</div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  solved = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  }</div>
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  }</div>
<div class="line"><a name="l00215"></a><span class="lineno"> 215</span>  }</div>
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  ecell->data->score *= failedExpansionScoreFactor_;</div>
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span>  }</div>
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span>  ecell->data->score *= failedExpansionScoreFactor_;</div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span>  disc.updateCell(ecell);</div>
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span>  }</div>
<div class="line"><a name="l00223"></a><span class="lineno"> 223</span>  </div>
<div class="line"><a name="l00224"></a><span class="lineno"> 224</span>  si_->freeState(xstate);</div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  </div>
<div class="line"><a name="l00226"></a><span class="lineno"> 226</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Created %u (%u start + %u goal) states in %u cells (%u start (%u on boundary) + %u goal (%u on "</span></div>
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span>  <span class="stringliteral">"boundary))"</span>,</div>
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  getName().c_str(), dStart_.getMotionCount() + dGoal_.getMotionCount(), dStart_.getMotionCount(),</div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  dGoal_.getMotionCount(), dStart_.getCellCount() + dGoal_.getCellCount(), dStart_.getCellCount(),</div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span>  dStart_.getGrid().countExternal(), dGoal_.getCellCount(), dGoal_.getGrid().countExternal());</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  </div>
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span>  <span class="keywordflow">return</span> solved ? <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a20f8c901516c72e258d43d7156fe8e28">base::PlannerStatus::EXACT_SOLUTION</a> : <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a620a03eebe49aa307140d6a4763278fd">base::PlannerStatus::TIMEOUT</a>;</div>
<div class="line"><a name="l00233"></a><span class="lineno"> 233</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"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#ae81ac9338565790508efaebbef3d8459"> 235</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#ae81ac9338565790508efaebbef3d8459">ompl::geometric::BKPIECE1::freeMotion</a>(<a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">Motion</a> *motion)</div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span> {</div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  <span class="keywordflow">if</span> (motion-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a> != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  si_->freeState(motion-><a class="code" href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">state</a>);</div>
<div class="line"><a name="l00239"></a><span class="lineno"> 239</span>  <span class="keyword">delete</span> motion;</div>
<div class="line"><a name="l00240"></a><span class="lineno"> 240</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"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#abca5f831bdfe09ab62001a434bda47b8"> 242</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#abca5f831bdfe09ab62001a434bda47b8">ompl::geometric::BKPIECE1::clear</a>()</div>
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span> {</div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  Planner::clear();</div>
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  </div>
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  sampler_.reset();</div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  dStart_.clear();</div>
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  dGoal_.clear();</div>
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span>  connectionPoint_ = std::make_pair<base::State *, base::State *>(<span class="keyword">nullptr</span>, <span class="keyword">nullptr</span>);</div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span> }</div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  </div>
<div class="line"><a name="l00252"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BKPIECE1.html#a10e5170141827497ad20dc06cc167e43"> 252</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BKPIECE1.html#a10e5170141827497ad20dc06cc167e43">ompl::geometric::BKPIECE1::getPlannerData</a>(<a class="code" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> &data)<span class="keyword"> const</span></div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  Planner::getPlannerData(data);</div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  dStart_.getPlannerData(data, 1, <span class="keyword">true</span>, <span class="keyword">nullptr</span>);</div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  dGoal_.getPlannerData(data, 2, <span class="keyword">false</span>, <span class="keyword">nullptr</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">// Insert the edge connecting the two trees</span></div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a06792592713e6463c4b9814f2a715b4c">vertexIndex</a>(connectionPoint_.first), data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a06792592713e6463c4b9814f2a715b4c">vertexIndex</a>(connectionPoint_.second));</div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span> }</div>
</div><!-- fragment --></div><!-- contents -->
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_1_1Motion_html_ab658fee6c2727e70f145252ec4df86c6"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#ab658fee6c2727e70f145252ec4df86c6">ompl::geometric::BKPIECE1::Motion::root</a></div><div class="ttdeci">const base::State * root</div><div class="ttdoc">The root state (start state) that leads to this motion.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00287">BKPIECE1.h:287</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4a47d769205044efa345184a640bd863ff"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a47d769205044efa345184a640bd863ff">ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE</a></div><div class="ttdeci">@ UNRECOGNIZED_GOAL_TYPE</div><div class="ttdoc">The goal is of a type that a planner does not recognize.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00188">PlannerStatus.h:188</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1SelfConfig_html_a65bff53ea4bc6f158342a856175ab9a6"><div class="ttname"><a href="classompl_1_1tools_1_1SelfConfig.html#a65bff53ea4bc6f158342a856175ab9a6">ompl::tools::SelfConfig::configurePlannerRange</a></div><div class="ttdeci">void configurePlannerRange(double &range)</div><div class="ttdoc">Compute what a good length for motion segments is.</div><div class="ttdef"><b>Definition:</b> <a href="SelfConfig_8cpp_source.html#l00225">SelfConfig.cpp:225</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_1_1Motion_html"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html">ompl::geometric::BKPIECE1::Motion</a></div><div class="ttdoc">Representation of a motion for this algorithm.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00274">BKPIECE1.h:274</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_ae81ac9338565790508efaebbef3d8459"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#ae81ac9338565790508efaebbef3d8459">ompl::geometric::BKPIECE1::freeMotion</a></div><div class="ttdeci">void freeMotion(Motion *motion)</div><div class="ttdoc">Free the memory for a motion.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00235">BKPIECE1.cpp:235</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a2cf588b5cd49be01cc43c576794c499c"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a2cf588b5cd49be01cc43c576794c499c">ompl::geometric::BKPIECE1::solve</a></div><div class="ttdeci">base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc) override</div><div class="ttdoc">Function that can solve the motion planning problem. This function can be called multiple times on th...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00076">BKPIECE1.cpp:76</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="State_8h_source.html#l00113">State.h:113</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1SelfConfig_html"><div class="ttname"><a href="classompl_1_1tools_1_1SelfConfig.html">ompl::tools::SelfConfig</a></div><div class="ttdoc">This class contains methods that automatically configure various parameters for motion planning....</div><div class="ttdef"><b>Definition:</b> <a href="SelfConfig_8h_source.html#l00123">SelfConfig.h:123</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_1_1Motion_html_a31d66a709c8a16e44787f019c9fc13b2"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a31d66a709c8a16e44787f019c9fc13b2">ompl::geometric::BKPIECE1::Motion::parent</a></div><div class="ttdeci">Motion * parent</div><div class="ttdoc">The parent motion in the exploration tree.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00293">BKPIECE1.h:293</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a1cec5e62c6aff0aea1ffef10337c0eb1"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a1cec5e62c6aff0aea1ffef10337c0eb1">ompl::geometric::BKPIECE1::getMinValidPathFraction</a></div><div class="ttdeci">double getMinValidPathFraction() const</div><div class="ttdoc">Get the value of the fraction set by setMinValidPathFraction()</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00260">BKPIECE1.h:260</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1Discretization_html_a86c80c67138c62e3da31dc5e42e0726b"><div class="ttname"><a href="classompl_1_1geometric_1_1Discretization.html#a86c80c67138c62e3da31dc5e42e0726b">ompl::geometric::Discretization::Cell</a></div><div class="ttdeci">typename Grid::Cell Cell</div><div class="ttdoc">The datatype for the maintained grid cells.</div><div class="ttdef"><b>Definition:</b> <a href="Discretization_8h_source.html#l00203">Discretization.h:203</a></div></div>
<div class="ttc" id="agroup__logging_html_ga04bc36d1b8c57ad7e13a8a48451a3a05"><div class="ttname"><a href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a></div><div class="ttdeci">#define OMPL_INFORM(fmt,...)</div><div class="ttdoc">Log a formatted information string.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00068">Console.h:68</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4a620a03eebe49aa307140d6a4763278fd"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a620a03eebe49aa307140d6a4763278fd">ompl::base::PlannerStatus::TIMEOUT</a></div><div class="ttdeci">@ TIMEOUT</div><div class="ttdoc">The planner failed to find a solution.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00190">PlannerStatus.h:190</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_ad01e749cab8b9096d01e8f9f3ca35f61"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#ad01e749cab8b9096d01e8f9f3ca35f61">ompl::geometric::BKPIECE1::getRange</a></div><div class="ttdeci">double getRange() const</div><div class="ttdoc">Get the range the planner is using.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00208">BKPIECE1.h:208</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1Discretization_html_a6ac71e099d8a69dc6c2ee5ff1736a277"><div class="ttname"><a href="classompl_1_1geometric_1_1Discretization.html#a6ac71e099d8a69dc6c2ee5ff1736a277">ompl::geometric::Discretization::addMotion</a></div><div class="ttdeci">unsigned int addMotion(Motion *motion, const Coord &coord, double dist=0.0)</div><div class="ttdoc">Add a motion to the grid containing motions. As a hint, dist specifies the distance to the goal from ...</div><div class="ttdef"><b>Definition:</b> <a href="Discretization_8h_source.html#l00289">Discretization.h:289</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_ab803b4859de12fd5788e87b99c672679"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#ab803b4859de12fd5788e87b99c672679">ompl::geometric::BKPIECE1::setRange</a></div><div class="ttdeci">void setRange(double distance)</div><div class="ttdoc">Set the range the planner is supposed to use.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00202">BKPIECE1.h:202</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#l00238">PlannerData.h:238</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a1e61534ba2f912016e00d94cfc5449e5"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a1e61534ba2f912016e00d94cfc5449e5">ompl::geometric::BKPIECE1::BKPIECE1</a></div><div class="ttdeci">BKPIECE1(const base::SpaceInformationPtr &si)</div><div class="ttdoc">Constructor.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00042">BKPIECE1.cpp:42</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_af93f42bd3ebf86547cfcb61ab1280e99"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#af93f42bd3ebf86547cfcb61ab1280e99">ompl::geometric::BKPIECE1::getFailedExpansionCellScoreFactor</a></div><div class="ttdeci">double getFailedExpansionCellScoreFactor() const</div><div class="ttdoc">Get the factor that is multiplied to a cell's score if extending a motion from that cell failed.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00243">BKPIECE1.h:243</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#l00127">PlannerTerminationCondition.h:127</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4a2e2b2b7e02900c4417af0ecea272c637"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a2e2b2b7e02900c4417af0ecea272c637">ompl::base::PlannerStatus::INVALID_GOAL</a></div><div class="ttdeci">@ INVALID_GOAL</div><div class="ttdoc">Invalid goal state.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00186">PlannerStatus.h:186</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_a06792592713e6463c4b9814f2a715b4c"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#a06792592713e6463c4b9814f2a715b4c">ompl::base::PlannerData::vertexIndex</a></div><div class="ttdeci">unsigned int vertexIndex(const PlannerDataVertex &v) const</div><div class="ttdoc">Return the index for the vertex associated with the given data. INVALID_INDEX is returned if this ver...</div><div class="ttdef"><b>Definition:</b> <a href="src_2ompl_2base_2src_2PlannerData_8cpp_source.html#l00315">PlannerData.cpp:315</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_abca5f831bdfe09ab62001a434bda47b8"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#abca5f831bdfe09ab62001a434bda47b8">ompl::geometric::BKPIECE1::clear</a></div><div class="ttdeci">void clear() override</div><div class="ttdoc">Clear all internal datastructures. Planner settings are not affected. Subsequent calls to solve() wil...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00242">BKPIECE1.cpp:242</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#l00112">PlannerStatus.h:112</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_1_1Motion_html_a4a6799d168bbc9ee73504b56ddc8c34e"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1_1_1Motion.html#a4a6799d168bbc9ee73504b56ddc8c34e">ompl::geometric::BKPIECE1::Motion::state</a></div><div class="ttdeci">base::State * state</div><div class="ttdoc">The state contained by this motion.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00290">BKPIECE1.h:290</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a1cc89cb07e13a333f6eed645a3dfcda3"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a1cc89cb07e13a333f6eed645a3dfcda3">ompl::geometric::BKPIECE1::setMinValidPathFraction</a></div><div class="ttdeci">void setMinValidPathFraction(double fraction)</div><div class="ttdoc">When extending a motion, the planner can decide to keep the first valid part of it,...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00254">BKPIECE1.h:254</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1Discretization_html_a8db183fa4a3231509336ffb7057805df"><div class="ttname"><a href="classompl_1_1geometric_1_1Discretization.html#a8db183fa4a3231509336ffb7057805df">ompl::geometric::Discretization::selectMotion</a></div><div class="ttdeci">void selectMotion(Motion *&smotion, Cell *&scell)</div><div class="ttdoc">Select a motion and the cell it is part of from the grid of motions. This is where preference is give...</div><div class="ttdef"><b>Definition:</b> <a href="Discretization_8h_source.html#l00320">Discretization.h:320</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1Discretization_html_a2dac26349b7da7fe428522518dfea7dc"><div class="ttname"><a href="classompl_1_1geometric_1_1Discretization.html#a2dac26349b7da7fe428522518dfea7dc">ompl::geometric::Discretization::Coord</a></div><div class="ttdeci">typename Grid::Coord Coord</div><div class="ttdoc">The datatype for the maintained grid coordinates.</div><div class="ttdef"><b>Definition:</b> <a href="Discretization_8h_source.html#l00206">Discretization.h:206</a></div></div>
<div class="ttc" id="anamespaceompl_1_1base_html_a1620a159019faf720c550eeca5723f55a6fb685fa51055688c4e130094225b7f9"><div class="ttname"><a href="namespaceompl_1_1base.html#a1620a159019faf720c550eeca5723f55a6fb685fa51055688c4e130094225b7f9">ompl::base::GOAL_SAMPLEABLE_REGION</a></div><div class="ttdeci">@ GOAL_SAMPLEABLE_REGION</div><div class="ttdoc">This bit is set if casting to sampleable goal regions (ompl::base::GoalSampleableRegion) is possible.</div><div class="ttdef"><b>Definition:</b> <a href="GoalTypes_8h_source.html#l00152">GoalTypes.h:152</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4a20f8c901516c72e258d43d7156fe8e28"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a20f8c901516c72e258d43d7156fe8e28">ompl::base::PlannerStatus::EXACT_SOLUTION</a></div><div class="ttdeci">@ EXACT_SOLUTION</div><div class="ttdoc">The planner found an exact solution.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00194">PlannerStatus.h:194</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a06f49930fd458b8ff60626a1f0b1b775"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a06f49930fd458b8ff60626a1f0b1b775">ompl::geometric::BKPIECE1::setFailedExpansionCellScoreFactor</a></div><div class="ttdeci">void setFailedExpansionCellScoreFactor(double factor)</div><div class="ttdoc">When extending a motion from a cell, the extension can be successful or it can fail....</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00236">BKPIECE1.h:236</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a6dd67ede6c67a142ff0270ec91b3a2d4"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a6dd67ede6c67a142ff0270ec91b3a2d4">ompl::geometric::BKPIECE1::getBorderFraction</a></div><div class="ttdeci">double getBorderFraction() const</div><div class="ttdoc">Get the fraction of time to focus exploration on boundary.</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00227">BKPIECE1.h:227</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1SelfConfig_html_a6af441eace888354bcc5afe172561d62"><div class="ttname"><a href="classompl_1_1tools_1_1SelfConfig.html#a6af441eace888354bcc5afe172561d62">ompl::tools::SelfConfig::configureProjectionEvaluator</a></div><div class="ttdeci">void configureProjectionEvaluator(base::ProjectionEvaluatorPtr &proj)</div><div class="ttdoc">If proj is undefined, it is set to the default projection reported by base::StateSpace::getDefaultPro...</div><div class="ttdef"><b>Definition:</b> <a href="SelfConfig_8cpp_source.html#l00231">SelfConfig.cpp:231</a></div></div>
<div class="ttc" id="agroup__logging_html_ga05ad3ae88188e7f248748785afd2b882"><div class="ttname"><a href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a></div><div class="ttdeci">#define OMPL_ERROR(fmt,...)</div><div class="ttdoc">Log a formatted error string.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00064">Console.h:64</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_aa724226c3dec34b09cfa9a57e94b4679"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#aa724226c3dec34b09cfa9a57e94b4679">ompl::geometric::BKPIECE1::setup</a></div><div class="ttdeci">void setup() override</div><div class="ttdoc">Perform extra configuration steps, if needed. This call will also issue a call to ompl::base::SpaceIn...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00060">BKPIECE1.cpp:60</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1Discretization_html"><div class="ttname"><a href="classompl_1_1geometric_1_1Discretization.html">ompl::geometric::Discretization</a></div><div class="ttdoc">One-level discretization used for KPIECE.</div><div class="ttdef"><b>Definition:</b> <a href="Discretization_8h_source.html#l00122">Discretization.h:122</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_ac09c21494a8c7db500ef1a66bbbb1aa7"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">ompl::base::PlannerData::addEdge</a></div><div class="ttdeci">virtual bool addEdge(unsigned int v1, unsigned int v2, const PlannerDataEdge &edge=PlannerDataEdge(), Cost weight=Cost(1.0))</div><div class="ttdoc">Adds a directed edge between the given vertex indexes. An optional edge structure and weight can be s...</div><div class="ttdef"><b>Definition:</b> <a href="src_2ompl_2base_2src_2PlannerData_8cpp_source.html#l00432">PlannerData.cpp:432</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1GoalSampleableRegion_html"><div class="ttname"><a href="classompl_1_1base_1_1GoalSampleableRegion.html">ompl::base::GoalSampleableRegion</a></div><div class="ttdoc">Abstract definition of a goal region that can be sampled.</div><div class="ttdef"><b>Definition:</b> <a href="GoalSampleableRegion_8h_source.html#l00111">GoalSampleableRegion.h:111</a></div></div>
<div class="ttc" id="aclassompl_1_1Exception_html"><div class="ttname"><a href="classompl_1_1Exception.html">ompl::Exception</a></div><div class="ttdoc">The exception type for ompl.</div><div class="ttdef"><b>Definition:</b> <a href="Exception_8h_source.html#l00078">Exception.h:78</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a10e5170141827497ad20dc06cc167e43"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a10e5170141827497ad20dc06cc167e43">ompl::geometric::BKPIECE1::getPlannerData</a></div><div class="ttdeci">void getPlannerData(base::PlannerData &data) const override</div><div class="ttdoc">Get information about the current run of the motion planner. Repeated calls to this function will upd...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8cpp_source.html#l00252">BKPIECE1.cpp:252</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4a1f20d012b563fc223902e24a8bcd7547"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a1f20d012b563fc223902e24a8bcd7547">ompl::base::PlannerStatus::INVALID_START</a></div><div class="ttdeci">@ INVALID_START</div><div class="ttdoc">Invalid start state or no start state specified.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00184">PlannerStatus.h:184</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BKPIECE1_html_a57e4e557bbd43543c4fe5d5d3733b443"><div class="ttname"><a href="classompl_1_1geometric_1_1BKPIECE1.html#a57e4e557bbd43543c4fe5d5d3733b443">ompl::geometric::BKPIECE1::setBorderFraction</a></div><div class="ttdeci">void setBorderFraction(double bp)</div><div class="ttdoc">Set the fraction of time for focusing on the border (between 0 and 1). This is the minimum fraction u...</div><div class="ttdef"><b>Definition:</b> <a href="BKPIECE1_8h_source.html#l00219">BKPIECE1.h:219</a></div></div>
</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.8.17
</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>