-
Notifications
You must be signed in to change notification settings - Fork 1
/
BiRLRT_8cpp_source.html
541 lines (539 loc) · 84.7 KB
/
BiRLRT_8cpp_source.html
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
<!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/rlrt/src/BiRLRT.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_25f044b688f1bb469f67c75d7f248291.html">rlrt</a></li><li class="navelem"><a class="el" href="dir_d2698f719a9a834a650933e20939c263.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">BiRLRT.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) 2015, 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 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: Ryan Luna */</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/rlrt/BiRLRT.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 <limits></span></div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span>  </div>
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> ompl::geometric::BiRLRT::BiRLRT(<span class="keyword">const</span> base::SpaceInformationPtr &si) : base::Planner(si, <span class="stringliteral">"BiRLRT"</span>)</div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span> {</div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.<a class="code" href="structompl_1_1base_1_1PlannerSpecs.html#ae2facc9260851b161577e36f5a4baefc">approximateSolutions</a> = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span>  <a class="code" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.<a class="code" href="structompl_1_1base_1_1PlannerSpecs.html#abe3ce1c340ba64c14644b0cace72907d">directed</a> = <span class="keyword">true</span>;</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>  Planner::declareParam<double>(<span class="stringliteral">"range"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a4412f7ef3e5c909887553fef40ce08c7">BiRLRT::setRange</a>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a8e989e73f8210c7d64a933f33877b5b1">BiRLRT::getRange</a>, <span class="stringliteral">"0.:1.:10000."</span>);</div>
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span>  Planner::declareParam<double>(<span class="stringliteral">"max_dist_near"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a0739548abde6eef5319a9356109e2e12">BiRLRT::setMaxDistanceNear</a>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a28101586165f4c288cf898a3288357b7">BiRLRT::getMaxDistanceNear</a>,</div>
<div class="line"><a name="l00049"></a><span class="lineno"> 49</span>  <span class="stringliteral">"0.:0.1:10."</span>);</div>
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span>  Planner::declareParam<bool>(<span class="stringliteral">"keep_last_valid"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a10f2c95c70803b5f7ea797269cf84fff">BiRLRT::setKeepLast</a>, &<a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a9d8454fd6e4aed25ab9a626dc1324884">BiRLRT::getKeepLast</a>, <span class="stringliteral">"0,1"</span>);</div>
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span> }</div>
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  </div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span> ompl::geometric::BiRLRT::~BiRLRT()</div>
<div class="line"><a name="l00054"></a><span class="lineno"> 54</span> {</div>
<div class="line"><a name="l00055"></a><span class="lineno"> 55</span>  freeMemory();</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"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#ad84a729b14bcc7879f677a875c92a732"> 58</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#ad84a729b14bcc7879f677a875c92a732">ompl::geometric::BiRLRT::clear</a>()</div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span> {</div>
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  Planner::clear();</div>
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span>  sampler_.reset();</div>
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  freeMemory();</div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</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="l00064"></a><span class="lineno"> 64</span> }</div>
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  </div>
<div class="line"><a name="l00066"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#aa33ba88ac8326dea8d015de44cd92a13"> 66</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#aa33ba88ac8326dea8d015de44cd92a13">ompl::geometric::BiRLRT::setup</a>()</div>
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span> {</div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span>  Planner::setup();</div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  <a class="code" href="classompl_1_1tools_1_1SelfConfig.html">tools::SelfConfig</a> sc(si_, getName());</div>
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span>  </div>
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span>  <span class="keywordflow">if</span> (range_ < 1e-4)</div>
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span>  sc.<a class="code" href="classompl_1_1tools_1_1SelfConfig.html#a65bff53ea4bc6f158342a856175ab9a6">configurePlannerRange</a>(range_);</div>
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  </div>
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span>  <span class="keywordflow">if</span> (maxDistNear_ < 1e-4)</div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  maxDistNear_ = range_ / 20.0; <span class="comment">// make this pretty small</span></div>
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span> }</div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  </div>
<div class="line"><a name="l00078"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#ae6540de93e17d53e24e9240c6e44c2db"> 78</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#ae6540de93e17d53e24e9240c6e44c2db">ompl::geometric::BiRLRT::freeMemory</a>()</div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span> {</div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : tStart_)</div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  {</div>
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  <span class="keywordflow">if</span> (motion->state != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  si_->freeState(motion->state);</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  <span class="keyword">delete</span> motion;</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>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : tGoal_)</div>
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  {</div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  <span class="keywordflow">if</span> (motion->state != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  si_->freeState(motion->state);</div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  <span class="keyword">delete</span> motion;</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  }</div>
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  </div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  tStart_.clear();</div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  tGoal_.clear();</div>
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span> }</div>
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  </div>
<div class="line"><a name="l00098"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#a2a8f50deb80b9918b7f57b39f02386d4"> 98</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a2a8f50deb80b9918b7f57b39f02386d4">ompl::geometric::BiRLRT::growTreeRangeLimited</a>(std::vector<Motion *> &tree, <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *xmotion)</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>  assert(tree.size() > 0);</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  </div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  <span class="comment">// select a state from tree to expand from</span></div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *randomMotion = tree[rng_.uniformInt(0, tree.size() - 1)];</div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  </div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  <span class="comment">// Sample a random direction. Limit length of motion to range_, if necessary</span></div>
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  sampler_->sampleUniform(xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  <span class="keywordtype">double</span> d = si_->distance(randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  <span class="keywordflow">if</span> (d > range_)</div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  si_->getStateSpace()->interpolate(randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, range_ / d, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  </div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  <span class="keywordflow">if</span> (si_->checkMotion(randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>))</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="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00115"></a><span class="lineno"> 115</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#af50c6f412c9adea8f9fabdafaca4d4fa">parent</a> = randomMotion;</div>
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a> = randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a>;</div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  </div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  tree.push_back(motion);</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  <span class="keywordflow">return</span> <span class="keyword">true</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>  </div>
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span> }</div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  </div>
<div class="line"><a name="l00126"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#a46a9a1be7d607738ca1594df4011e28f"> 126</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a46a9a1be7d607738ca1594df4011e28f">ompl::geometric::BiRLRT::growTreeKeepLast</a>(std::vector<Motion *> &tree, <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *xmotion,</div>
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  std::pair<ompl::base::State *, double> &lastValid)</div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span> {</div>
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  assert(tree.size() > 0);</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="comment">// select a state from tree to expand from</span></div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *randomMotion = tree[rng_.uniformInt(0, tree.size() - 1)];</div>
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span>  </div>
<div class="line"><a name="l00134"></a><span class="lineno"> 134</span>  <span class="comment">// Sample a random state.</span></div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span>  sampler_->sampleUniform(xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span>  </div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span>  lastValid.second = 0.0;</div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  <span class="keywordtype">bool</span> valid = si_->checkMotion(randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, lastValid);</div>
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span>  <span class="keywordflow">if</span> (valid || lastValid.second > 1e-3)</div>
<div class="line"><a name="l00140"></a><span class="lineno"> 140</span>  {</div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span>  <span class="comment">// create a new motion</span></div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span>  si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, valid ? xmotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a> : lastValid.first);</div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#af50c6f412c9adea8f9fabdafaca4d4fa">parent</a> = randomMotion;</div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a> = randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a>;</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>  tree.push_back(motion);</div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  }</div>
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span>  </div>
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</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>  </div>
<div class="line"><a name="l00154"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#afedc17485c2f909fa35af14bce43a26d"> 154</a></span> <span class="keywordtype">int</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#afedc17485c2f909fa35af14bce43a26d">ompl::geometric::BiRLRT::connectToTree</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *motion, std::vector<Motion *> &tree)</div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span> {</div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span>  assert(tree.size() > 0);</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="keywordtype">int</span> checks = tree.size() > 1 ? ceil(<a class="code" href="namespaceompl_1_1msg.html#affe7852f27c06f98af7eb2579f1e5350">log</a>(tree.size())) : 1;</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="keywordflow">for</span> (<span class="keywordtype">int</span> i = 0; i < checks; ++i)</div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  {</div>
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span>  <span class="comment">// select a state from tree to expand from</span></div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  <span class="keywordtype">int</span> randIndex = rng_.uniformInt(0, tree.size() - 1);</div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *randomMotion = tree[randIndex];</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>  <span class="keywordflow">if</span> (si_->checkMotion(randomMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>))</div>
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  <span class="keywordflow">return</span> randIndex;</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>  </div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  <span class="keywordflow">return</span> -1; <span class="comment">// failed connection</span></div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span> }</div>
<div class="line"><a name="l00172"></a><span class="lineno"> 172</span>  </div>
<div class="line"><a name="l00173"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#a4fb81bbdfed131fcd0dc575d5736916e"> 173</a></span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#a4fb81bbdfed131fcd0dc575d5736916e">ompl::geometric::BiRLRT::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="l00174"></a><span class="lineno"> 174</span> {</div>
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  checkValidity();</div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</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="l00177"></a><span class="lineno"> 177</span>  <span class="keywordflow">if</span> (!goal)</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>  <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="l00180"></a><span class="lineno"> 180</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="l00181"></a><span class="lineno"> 181</span>  }</div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  </div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</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="l00184"></a><span class="lineno"> 184</span>  {</div>
<div class="line"><a name="l00185"></a><span class="lineno"> 185</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span>  si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, st);</div>
<div class="line"><a name="l00187"></a><span class="lineno"> 187</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a> = motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>;</div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  tStart_.push_back(motion);</div>
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  }</div>
<div class="line"><a name="l00190"></a><span class="lineno"> 190</span>  </div>
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  <span class="keywordflow">if</span> (tStart_.size() == 0)</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>  <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="l00194"></a><span class="lineno"> 194</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="l00195"></a><span class="lineno"> 195</span>  }</div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  </div>
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  <span class="keywordflow">if</span> (!sampler_)</div>
<div class="line"><a name="l00198"></a><span class="lineno"> 198</span>  sampler_ = si_->allocStateSampler();</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> (!goal->couldSample())</div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  {</div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  <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="l00203"></a><span class="lineno"> 203</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="l00204"></a><span class="lineno"> 204</span>  }</div>
<div class="line"><a name="l00205"></a><span class="lineno"> 205</span>  </div>
<div class="line"><a name="l00206"></a><span class="lineno"> 206</span>  <a class="code" href="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="l00207"></a><span class="lineno"> 207</span>  (<span class="keywordtype">int</span>)(tStart_.size() + tGoal_.size()));</div>
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  <span class="keywordflow">if</span> (keepLast_)</div>
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: keeping last valid state"</span>, getName().c_str());</div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: tree is range limited"</span>, getName().c_str());</div>
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  </div>
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  std::vector<Motion *> *tree, *otherTree;</div>
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  tree = &tStart_;</div>
<div class="line"><a name="l00215"></a><span class="lineno"> 215</span>  otherTree = &tGoal_;</div>
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span>  <span class="keywordtype">bool</span> solved = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  </div>
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span>  <span class="keyword">auto</span> xmotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span>  </div>
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span>  std::pair<ompl::base::State *, double> lastValid;</div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span>  lastValid.first = si_->allocState();</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>  <span class="keywordflow">while</span> (ptc == <span class="keyword">false</span> && solved == <span class="keyword">false</span>)</div>
<div class="line"><a name="l00224"></a><span class="lineno"> 224</span>  {</div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  <span class="keywordflow">if</span> (tGoal_.size() == 0 || pis_.getSampledGoalsCount() < tGoal_.size() / 2)</div>
<div class="line"><a name="l00226"></a><span class="lineno"> 226</span>  {</div>
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *st = tGoal_.size() == 0 ? pis_.nextGoal(ptc) : pis_.nextGoal();</div>
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  <span class="keywordflow">if</span> (st)</div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  {</div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  si_->copyState(motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, st);</div>
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a> = motion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>;</div>
<div class="line"><a name="l00233"></a><span class="lineno"> 233</span>  tGoal_.push_back(motion);</div>
<div class="line"><a name="l00234"></a><span class="lineno"> 234</span>  }</div>
<div class="line"><a name="l00235"></a><span class="lineno"> 235</span>  </div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  <span class="keywordflow">if</span> (tGoal_.size() == 0)</div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  {</div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  <a class="code" href="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="l00239"></a><span class="lineno"> 239</span>  <span class="keywordflow">break</span>;</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"> 242</span>  </div>
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span>  <span class="keywordtype">bool</span> expanded = keepLast_ ? growTreeKeepLast(*tree, xmotion, lastValid) : growTreeRangeLimited(*tree, xmotion);</div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  <span class="keywordflow">if</span> (expanded)</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>  <span class="keywordtype">int</span> connectionIdx = connectToTree(tree->back(), *otherTree);</div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  <span class="keywordflow">if</span> (connectionIdx >= 0)</div>
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  {</div>
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span>  <span class="comment">// there is a solution path. construct it.</span></div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *startMotion = tree == &tStart_ ? tree->back() : otherTree->at(connectionIdx);</div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *goalMotion = tree == &tStart_ ? otherTree->at(connectionIdx) : tree->back();</div>
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span>  </div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span>  <span class="comment">// start and goal pair is not valid for this problem</span></div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  <span class="keywordflow">if</span> (!goal->isStartGoalPairValid(startMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a>, goalMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">root</a>))</div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  <span class="keywordflow">continue</span>;</div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  </div>
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span>  connectionPoint_ = std::make_pair(startMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>, goalMotion-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">state</a>);</div>
<div class="line"><a name="l00258"></a><span class="lineno"> 258</span>  </div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  <a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">Motion</a> *solution = startMotion;</div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span>  std::vector<Motion *> mpath1;</div>
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  <span class="keywordflow">while</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00262"></a><span class="lineno"> 262</span>  {</div>
<div class="line"><a name="l00263"></a><span class="lineno"> 263</span>  mpath1.push_back(solution);</div>
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  solution = solution-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#af50c6f412c9adea8f9fabdafaca4d4fa">parent</a>;</div>
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  }</div>
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  </div>
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span>  solution = goalMotion;</div>
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span>  std::vector<Motion *> mpath2;</div>
<div class="line"><a name="l00269"></a><span class="lineno"> 269</span>  <span class="keywordflow">while</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span>  {</div>
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span>  mpath2.push_back(solution);</div>
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span>  solution = solution-><a class="code" href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#af50c6f412c9adea8f9fabdafaca4d4fa">parent</a>;</div>
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span>  }</div>
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span>  </div>
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span>  <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html">PathGeometric</a> *path = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1PathGeometric.html">PathGeometric</a>(si_);</div>
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  path->getStates().reserve(mpath1.size() + mpath2.size());</div>
<div class="line"><a name="l00277"></a><span class="lineno"> 277</span>  <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath1.size() - 1; i >= 0; --i)</div>
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span>  path->append(mpath1[i]->state);</div>
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0; i < mpath2.size(); ++i)</div>
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  path->append(mpath2[i]->state);</div>
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  </div>
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  pdef_->addSolutionPath(base::PathPtr(path), <span class="keyword">false</span>, 0.0, getName());</div>
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  solved = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00284"></a><span class="lineno"> 284</span>  }</div>
<div class="line"><a name="l00285"></a><span class="lineno"> 285</span>  }</div>
<div class="line"><a name="l00286"></a><span class="lineno"> 286</span>  std::swap(tree, otherTree);</div>
<div class="line"><a name="l00287"></a><span class="lineno"> 287</span>  }</div>
<div class="line"><a name="l00288"></a><span class="lineno"> 288</span>  </div>
<div class="line"><a name="l00289"></a><span class="lineno"> 289</span>  si_->freeState(xmotion->state);</div>
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span>  <span class="keyword">delete</span> xmotion;</div>
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  si_->freeState(lastValid.first);</div>
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span>  </div>
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Created %u states (%u start + %u goal)"</span>, getName().c_str(), tStart_.size() + tGoal_.size(),</div>
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span>  tStart_.size(), tGoal_.size());</div>
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span>  </div>
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span>  <span class="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="l00297"></a><span class="lineno"> 297</span> }</div>
<div class="line"><a name="l00298"></a><span class="lineno"> 298</span>  </div>
<div class="line"><a name="l00299"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiRLRT.html#acf82ca521b99c931cefadaba3d739dff"> 299</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiRLRT.html#acf82ca521b99c931cefadaba3d739dff">ompl::geometric::BiRLRT::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="l00300"></a><span class="lineno"> 300</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span>  Planner::getPlannerData(data);</div>
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span>  </div>
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : tStart_)</div>
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span>  {</div>
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span>  <span class="keywordflow">if</span> (motion->parent == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a2eea84456784452486aa0065af391f47">addStartVertex</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state, 1));</div>
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span>  {</div>
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->parent->state, 1), <a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state, 1));</div>
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span>  }</div>
<div class="line"><a name="l00311"></a><span class="lineno"> 311</span>  }</div>
<div class="line"><a name="l00312"></a><span class="lineno"> 312</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : tGoal_)</div>
<div class="line"><a name="l00313"></a><span class="lineno"> 313</span>  {</div>
<div class="line"><a name="l00314"></a><span class="lineno"> 314</span>  <span class="keywordflow">if</span> (motion->parent == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a2eea84456784452486aa0065af391f47">addStartVertex</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state, 1));</div>
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span>  {</div>
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->parent->state, 1), <a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state, 1));</div>
<div class="line"><a name="l00319"></a><span class="lineno"> 319</span>  }</div>
<div class="line"><a name="l00320"></a><span class="lineno"> 320</span>  }</div>
<div class="line"><a name="l00321"></a><span class="lineno"> 321</span>  </div>
<div class="line"><a name="l00322"></a><span class="lineno"> 322</span>  <span class="comment">// Add the edge connecting the two trees</span></div>
<div class="line"><a name="l00323"></a><span class="lineno"> 323</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="l00324"></a><span class="lineno"> 324</span> }</div>
</div><!-- fragment --></div><!-- contents -->
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a9d8454fd6e4aed25ab9a626dc1324884"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a9d8454fd6e4aed25ab9a626dc1324884">ompl::geometric::BiRLRT::getKeepLast</a></div><div class="ttdeci">bool getKeepLast() const</div><div class="ttdoc">If true, the planner will not have the range limitation. Instead, if a collision is detected,...</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00201">BiRLRT.h:201</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_1_1Motion_html_af50c6f412c9adea8f9fabdafaca4d4fa"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#af50c6f412c9adea8f9fabdafaca4d4fa">ompl::geometric::BiRLRT::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="BiRLRT_8h_source.html#l00233">BiRLRT.h:233</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_ae6540de93e17d53e24e9240c6e44c2db"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#ae6540de93e17d53e24e9240c6e44c2db">ompl::geometric::BiRLRT::freeMemory</a></div><div class="ttdeci">void freeMemory()</div><div class="ttdoc">Free the memory allocated by this planner.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8cpp_source.html#l00078">BiRLRT.cpp:78</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_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_1geometric_1_1BiRLRT_html_afedc17485c2f909fa35af14bce43a26d"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#afedc17485c2f909fa35af14bce43a26d">ompl::geometric::BiRLRT::connectToTree</a></div><div class="ttdeci">int connectToTree(const Motion *motion, std::vector< Motion * > &tree)</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8cpp_source.html#l00154">BiRLRT.cpp:154</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_1BiRLRT_html_ad84a729b14bcc7879f677a875c92a732"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#ad84a729b14bcc7879f677a875c92a732">ompl::geometric::BiRLRT::clear</a></div><div class="ttdeci">virtual void clear()</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="BiRLRT_8cpp_source.html#l00058">BiRLRT.cpp:58</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a10f2c95c70803b5f7ea797269cf84fff"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a10f2c95c70803b5f7ea797269cf84fff">ompl::geometric::BiRLRT::setKeepLast</a></div><div class="ttdeci">void setKeepLast(bool keepLast)</div><div class="ttdoc">Set whether the planner will use the range or keep last heuristic. If keepLast = false,...</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00210">BiRLRT.h:210</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_aa33ba88ac8326dea8d015de44cd92a13"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#aa33ba88ac8326dea8d015de44cd92a13">ompl::geometric::BiRLRT::setup</a></div><div class="ttdeci">virtual void setup()</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="BiRLRT_8cpp_source.html#l00066">BiRLRT.cpp:66</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_1_1Motion_html"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html">ompl::geometric::BiRLRT::Motion</a></div><div class="ttdoc">A motion (tree node) with parent pointer.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00219">BiRLRT.h:219</a></div></div>
<div class="ttc" id="anamespaceompl_1_1msg_html_affe7852f27c06f98af7eb2579f1e5350"><div class="ttname"><a href="namespaceompl_1_1msg.html#affe7852f27c06f98af7eb2579f1e5350">ompl::msg::log</a></div><div class="ttdeci">void log(const char *file, int line, LogLevel level, const char *m,...)</div><div class="ttdoc">Root level logging function. This should not be invoked directly, but rather used via a logging macro...</div><div class="ttdef"><b>Definition:</b> <a href="Console_8cpp_source.html#l00120">Console.cpp:120</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_1BiRLRT_html_a4412f7ef3e5c909887553fef40ce08c7"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a4412f7ef3e5c909887553fef40ce08c7">ompl::geometric::BiRLRT::setRange</a></div><div class="ttdeci">void setRange(double distance)</div><div class="ttdoc">Set the maximum distance between states in the tree.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00173">BiRLRT.h:173</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1PathGeometric_html"><div class="ttname"><a href="classompl_1_1geometric_1_1PathGeometric.html">ompl::geometric::PathGeometric</a></div><div class="ttdoc">Definition of a geometric path.</div><div class="ttdef"><b>Definition:</b> <a href="PathGeometric_8h_source.html#l00097">PathGeometric.h:97</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_1BiRLRT_html_a4fb81bbdfed131fcd0dc575d5736916e"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a4fb81bbdfed131fcd0dc575d5736916e">ompl::geometric::BiRLRT::solve</a></div><div class="ttdeci">virtual base::PlannerStatus solve(const base::PlannerTerminationCondition &ptc)</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="BiRLRT_8cpp_source.html#l00173">BiRLRT.cpp:173</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_1_1Motion_html_a99f6abe9e3ad1e54296b3433708d6675"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#a99f6abe9e3ad1e54296b3433708d6675">ompl::geometric::BiRLRT::Motion::root</a></div><div class="ttdeci">const base::State * root</div><div class="ttdoc">Pointer to the root of the tree this motion is connected to.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00236">BiRLRT.h:236</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="aclassompl_1_1base_1_1Planner_html_a4311ea7a0470f0e0f76cb1656d63e365"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">ompl::base::Planner::specs_</a></div><div class="ttdeci">PlannerSpecs specs_</div><div class="ttdoc">The specifications of the planner (its capabilities)</div><div class="ttdef"><b>Definition:</b> <a href="Planner_8h_source.html#l00486">Planner.h:486</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="astructompl_1_1base_1_1PlannerSpecs_html_abe3ce1c340ba64c14644b0cace72907d"><div class="ttname"><a href="structompl_1_1base_1_1PlannerSpecs.html#abe3ce1c340ba64c14644b0cace72907d">ompl::base::PlannerSpecs::directed</a></div><div class="ttdeci">bool directed</div><div class="ttdoc">Flag indicating whether the planner is able to account for the fact that the validity of a motion fro...</div><div class="ttdef"><b>Definition:</b> <a href="Planner_8h_source.html#l00269">Planner.h:269</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a28101586165f4c288cf898a3288357b7"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a28101586165f4c288cf898a3288357b7">ompl::geometric::BiRLRT::getMaxDistanceNear</a></div><div class="ttdeci">double getMaxDistanceNear() const</div><div class="ttdoc">Get the maximum distance (per dimension) when sampling near an existing state.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00193">BiRLRT.h:193</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_1_1Motion_html_ac3e5f970ccc0af55937613f87ee0916a"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT_1_1Motion.html#ac3e5f970ccc0af55937613f87ee0916a">ompl::geometric::BiRLRT::Motion::state</a></div><div class="ttdeci">base::State * state</div><div class="ttdoc">The state contained by the motion.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00230">BiRLRT.h:230</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_1BiRLRT_html_acf82ca521b99c931cefadaba3d739dff"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#acf82ca521b99c931cefadaba3d739dff">ompl::geometric::BiRLRT::getPlannerData</a></div><div class="ttdeci">virtual void getPlannerData(base::PlannerData &data) const</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="BiRLRT_8cpp_source.html#l00299">BiRLRT.cpp:299</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a0739548abde6eef5319a9356109e2e12"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a0739548abde6eef5319a9356109e2e12">ompl::geometric::BiRLRT::setMaxDistanceNear</a></div><div class="ttdeci">void setMaxDistanceNear(double dNear)</div><div class="ttdoc">Set the maximum distance (per dimension) when sampling near an existing state.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00186">BiRLRT.h:186</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a8e989e73f8210c7d64a933f33877b5b1"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a8e989e73f8210c7d64a933f33877b5b1">ompl::geometric::BiRLRT::getRange</a></div><div class="ttdeci">double getRange() const</div><div class="ttdoc">Get the maximum distance between states in the tree.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8h_source.html#l00179">BiRLRT.h:179</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_1BiRLRT_html_a46a9a1be7d607738ca1594df4011e28f"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a46a9a1be7d607738ca1594df4011e28f">ompl::geometric::BiRLRT::growTreeKeepLast</a></div><div class="ttdeci">bool growTreeKeepLast(std::vector< Motion * > &tree, Motion *xmotion, std::pair< base::State *, double > &lastValid)</div><div class="ttdoc">Try to grow the tree randomly. Return true if a new state was added.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8cpp_source.html#l00126">BiRLRT.cpp:126</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_a2eea84456784452486aa0065af391f47"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#a2eea84456784452486aa0065af391f47">ompl::base::PlannerData::addStartVertex</a></div><div class="ttdeci">unsigned int addStartVertex(const PlannerDataVertex &v)</div><div class="ttdoc">Adds the given vertex to the graph data, and marks it as a start vertex. The vertex index is returned...</div><div class="ttdef"><b>Definition:</b> <a href="src_2ompl_2base_2src_2PlannerData_8cpp_source.html#l00413">PlannerData.cpp:413</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiRLRT_html_a2a8f50deb80b9918b7f57b39f02386d4"><div class="ttname"><a href="classompl_1_1geometric_1_1BiRLRT.html#a2a8f50deb80b9918b7f57b39f02386d4">ompl::geometric::BiRLRT::growTreeRangeLimited</a></div><div class="ttdeci">bool growTreeRangeLimited(std::vector< Motion * > &tree, Motion *xmotion)</div><div class="ttdoc">Try to grow the tree randomly. Return true if a new state was added.</div><div class="ttdef"><b>Definition:</b> <a href="BiRLRT_8cpp_source.html#l00098">BiRLRT.cpp:98</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="astructompl_1_1base_1_1PlannerSpecs_html_ae2facc9260851b161577e36f5a4baefc"><div class="ttname"><a href="structompl_1_1base_1_1PlannerSpecs.html#ae2facc9260851b161577e36f5a4baefc">ompl::base::PlannerSpecs::approximateSolutions</a></div><div class="ttdeci">bool approximateSolutions</div><div class="ttdoc">Flag indicating whether the planner is able to compute approximate solutions.</div><div class="ttdef"><b>Definition:</b> <a href="Planner_8h_source.html#l00259">Planner.h:259</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="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_1base_1_1PlannerDataVertex_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerDataVertex.html">ompl::base::PlannerDataVertex</a></div><div class="ttdoc">Base class for a vertex in the PlannerData structure. All derived classes must implement the clone an...</div><div class="ttdef"><b>Definition:</b> <a href="base_2PlannerData_8h_source.html#l00122">PlannerData.h:122</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>