-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathBiTRRT_8cpp_source.html
More file actions
740 lines (738 loc) · 123 KB
/
BiTRRT_8cpp_source.html
File metadata and controls
740 lines (738 loc) · 123 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
<!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/rrt/src/BiTRRT.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_736ec1218ec11c17ebed8baec76dcd23.html">rrt</a></li><li class="navelem"><a class="el" href="dir_d338dba13966c9829e7850dc0578c858.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">BiTRRT.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 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: 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 <limits></span></div>
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span>  </div>
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="preprocessor">#include "ompl/geometric/planners/rrt/BiTRRT.h"</span></div>
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span> <span class="preprocessor">#include "ompl/base/goals/GoalSampleableRegion.h"</span></div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span> <span class="preprocessor">#include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"</span></div>
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> <span class="preprocessor">#include "ompl/tools/config/MagicConstants.h"</span></div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span> <span class="preprocessor">#include "ompl/tools/config/SelfConfig.h"</span></div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span>  </div>
<div class="line"><a name="l00045"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a2f3d18a363976e7345cbc28577018766"> 45</a></span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a2f3d18a363976e7345cbc28577018766">ompl::geometric::BiTRRT::BiTRRT</a>(<span class="keyword">const</span> base::SpaceInformationPtr &si) : base::Planner(si, <span class="stringliteral">"BiTRRT"</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>  <a class="code" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.<a class="code" href="structompl_1_1base_1_1PlannerSpecs.html#ae2facc9260851b161577e36f5a4baefc">approximateSolutions</a> = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00048"></a><span class="lineno"> 48</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="l00049"></a><span class="lineno"> 49</span>  </div>
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span>  Planner::declareParam<double>(<span class="stringliteral">"range"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#ad71f5b6833006f7e7fc008c51428d9bf">BiTRRT::setRange</a>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#ae2aabb326b63edc54d73ae640a8a8515">BiTRRT::getRange</a>, <span class="stringliteral">"0.:1.:10000."</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>  <span class="comment">// BiTRRT Specific Variables</span></div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a7d06fd3929104c9dca2a743b1f4cbddc">setTempChangeFactor</a>(0.1); <span class="comment">// how much to increase the temp each time</span></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>  Planner::declareParam<double>(<span class="stringliteral">"temp_change_factor"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a7d06fd3929104c9dca2a743b1f4cbddc">BiTRRT::setTempChangeFactor</a>,</div>
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span>  &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#afc2441e4deb2cf71c680db8838ab2ff8">BiTRRT::getTempChangeFactor</a>, <span class="stringliteral">"0.:.1:1."</span>);</div>
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span>  Planner::declareParam<double>(<span class="stringliteral">"init_temperature"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#af01edc2564a947c534f77011027826c2">BiTRRT::setInitTemperature</a>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a28456d8d144a225f25db1426822432f1">BiTRRT::getInitTemperature</a>);</div>
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span>  Planner::declareParam<double>(<span class="stringliteral">"frontier_threshold"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a21c3fa749ad83310b40988aa96357a8c">BiTRRT::setFrontierThreshold</a>,</div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span>  &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#aaa69d535612c856c194f0664eb0c08a2">BiTRRT::getFrontierThreshold</a>);</div>
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  Planner::declareParam<double>(<span class="stringliteral">"frontier_node_ratio"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a161724203e2d0ef60e38fe4237835ac4">BiTRRT::setFrontierNodeRatio</a>,</div>
<div class="line"><a name="l00061"></a><span class="lineno"> 61</span>  &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a242985410fb727f691033a274f400c9c">BiTRRT::getFrontierNodeRatio</a>);</div>
<div class="line"><a name="l00062"></a><span class="lineno"> 62</span>  Planner::declareParam<double>(<span class="stringliteral">"cost_threshold"</span>, <span class="keyword">this</span>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a8f7bbe64f7b08b9c986f189339ceb2d1">BiTRRT::setCostThreshold</a>, &<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a53f6a346df9177e79e91a6db06c7f328">BiTRRT::getCostThreshold</a>);</div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</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> ompl::geometric::BiTRRT::~BiTRRT()</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>  freeMemory();</div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span> }</div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  </div>
<div class="line"><a name="l00070"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#ac63536fa52ee81830fdaad13364c8c21"> 70</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#ac63536fa52ee81830fdaad13364c8c21">ompl::geometric::BiTRRT::freeMemory</a>()</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>  std::vector<Motion *> motions;</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> (tStart_)</div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  {</div>
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span>  tStart_->list(motions);</div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  {</div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  <span class="keywordflow">if</span> (motion->state != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  si_->freeState(motion->state);</div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  <span class="keyword">delete</span> motion;</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>  }</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  </div>
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  <span class="keywordflow">if</span> (tGoal_)</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>  tGoal_->list(motions);</div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  {</div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span>  <span class="keywordflow">if</span> (motion->state != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  si_->freeState(motion->state);</div>
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  <span class="keyword">delete</span> motion;</div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  }</div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  }</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="l00097"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a2376b591508ad0543c531e7dac06a426"> 97</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a2376b591508ad0543c531e7dac06a426">ompl::geometric::BiTRRT::clear</a>()</div>
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span> {</div>
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  Planner::clear();</div>
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span>  freeMemory();</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <span class="keywordflow">if</span> (tStart_)</div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  tStart_->clear();</div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  <span class="keywordflow">if</span> (tGoal_)</div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  tGoal_->clear();</div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span>  connectionPoint_ = std::make_pair<Motion *, Motion *>(<span class="keyword">nullptr</span>, <span class="keyword">nullptr</span>);</div>
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  </div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  <span class="comment">// TRRT specific variables</span></div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  temp_ = initTemperature_;</div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  nonfrontierCount_ = 1;</div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  frontierCount_ = 1; <span class="comment">// init to 1 to prevent division by zero error</span></div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  <span class="keywordflow">if</span> (opt_)</div>
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  bestCost_ = worstCost_ = opt_->identityCost();</div>
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span> }</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  </div>
<div class="line"><a name="l00115"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#abce500ace7b425fb85c99f6f216f12d6"> 115</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#abce500ace7b425fb85c99f6f216f12d6">ompl::geometric::BiTRRT::setup</a>()</div>
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span> {</div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  Planner::setup();</div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  <a class="code" href="classompl_1_1tools_1_1SelfConfig.html">tools::SelfConfig</a> sc(si_, getName());</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  </div>
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span>  <span class="comment">// Configuring the range of the planner</span></div>
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span>  <span class="keywordflow">if</span> (maxDistance_ < std::numeric_limits<double>::epsilon())</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>  sc.<a class="code" href="classompl_1_1tools_1_1SelfConfig.html#a65bff53ea4bc6f158342a856175ab9a6">configurePlannerRange</a>(maxDistance_);</div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  maxDistance_ *= <a class="code" href="namespaceompl_1_1magic.html#a3c9c3d6c0ee87fea2dbc5fa7484d15fa">magic::COST_MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION</a>;</div>
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span>  }</div>
<div class="line"><a name="l00126"></a><span class="lineno"> 126</span>  </div>
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  <span class="comment">// Configuring nearest neighbors structures for the planning trees</span></div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="keywordflow">if</span> (!tStart_)</div>
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  tStart_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(<span class="keyword">this</span>));</div>
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span>  <span class="keywordflow">if</span> (!tGoal_)</div>
<div class="line"><a name="l00131"></a><span class="lineno"> 131</span>  tGoal_.reset(tools::SelfConfig::getDefaultNearestNeighbors<Motion *>(<span class="keyword">this</span>));</div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span>  tStart_->setDistanceFunction([<span class="keyword">this</span>](<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *a, <span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *b)</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="keywordflow">return</span> distanceFunction(a, b);</div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span>  });</div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span>  tGoal_->setDistanceFunction([<span class="keyword">this</span>](<span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *a, <span class="keyword">const</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *b)</div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span>  {</div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  <span class="keywordflow">return</span> distanceFunction(a, b);</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>  </div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span>  <span class="comment">// Setup the optimization objective, if it isn't specified</span></div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span>  <span class="keywordflow">if</span> (!pdef_ || !pdef_->hasOptimizationObjective())</div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span>  {</div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: No optimization objective specified. Defaulting to mechanical work minimization."</span>,</div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span>  getName().c_str());</div>
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span>  opt_ = std::make_shared<base::MechanicalWorkOptimizationObjective>(si_);</div>
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span>  }</div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  opt_ = pdef_->getOptimizationObjective();</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="comment">// Set the threshold that decides if a new node is a frontier node or non-frontier node</span></div>
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span>  <span class="keywordflow">if</span> (frontierThreshold_ < std::numeric_limits<double>::epsilon())</div>
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span>  {</div>
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span>  frontierThreshold_ = si_->getMaximumExtent() * 0.01;</div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span>  <a class="code" href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a>(<span class="stringliteral">"%s: Frontier threshold detected to be %lf"</span>, getName().c_str(), frontierThreshold_);</div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</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="comment">// initialize TRRT specific variables</span></div>
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span>  temp_ = initTemperature_;</div>
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span>  nonfrontierCount_ = 1;</div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  frontierCount_ = 1; <span class="comment">// init to 1 to prevent division by zero error</span></div>
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span>  bestCost_ = worstCost_ = opt_->identityCost();</div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  connectionRange_ = 10.0 * si_->getStateSpace()->getLongestValidSegmentLength();</div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span> }</div>
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span>  </div>
<div class="line"><a name="l00166"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a6c900b2bbcfe22d0817928b1be743d5f"> 166</a></span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">ompl::geometric::BiTRRT::Motion</a> *<a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a6c900b2bbcfe22d0817928b1be743d5f">ompl::geometric::BiTRRT::addMotion</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *state, <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> &tree,</div>
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *parent)</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>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  si_->copyState(motion->state, state);</div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  motion->cost = opt_->stateCost(motion->state);</div>
<div class="line"><a name="l00172"></a><span class="lineno"> 172</span>  motion->parent = parent;</div>
<div class="line"><a name="l00173"></a><span class="lineno"> 173</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a> = parent != <span class="keyword">nullptr</span> ? parent-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a> : <span class="keyword">nullptr</span>;</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> (opt_->isCostBetterThan(motion->cost, bestCost_)) <span class="comment">// motion->cost is better than the existing best</span></div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  bestCost_ = motion->cost;</div>
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  <span class="keywordflow">if</span> (opt_->isCostBetterThan(worstCost_, motion->cost)) <span class="comment">// motion->cost is worse than the existing worst</span></div>
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  worstCost_ = motion->cost;</div>
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  </div>
<div class="line"><a name="l00180"></a><span class="lineno"> 180</span>  <span class="comment">// Add start motion to the tree</span></div>
<div class="line"><a name="l00181"></a><span class="lineno"> 181</span>  tree->add(motion);</div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  <span class="keywordflow">return</span> motion;</div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span> }</div>
<div class="line"><a name="l00184"></a><span class="lineno"> 184</span>  </div>
<div class="line"><a name="l00185"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a10a681d8fb04bc7250f2648b0206599e"> 185</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a10a681d8fb04bc7250f2648b0206599e">ompl::geometric::BiTRRT::transitionTest</a>(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Cost.html">base::Cost</a> &motionCost)</div>
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span> {</div>
<div class="line"><a name="l00187"></a><span class="lineno"> 187</span>  <span class="comment">// Disallow any cost that is not better than the cost threshold</span></div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  <span class="keywordflow">if</span> (!opt_->isCostBetterThan(motionCost, costThreshold_))</div>
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  <span class="keywordflow">return</span> <span class="keyword">false</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="comment">// Always accept if the cost is near or below zero</span></div>
<div class="line"><a name="l00192"></a><span class="lineno"> 192</span>  <span class="keywordflow">if</span> (motionCost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() < 1e-4)</div>
<div class="line"><a name="l00193"></a><span class="lineno"> 193</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  </div>
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  <span class="keywordtype">double</span> dCost = motionCost.<a class="code" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>();</div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span>  <span class="keywordtype">double</span> transitionProbability = exp(-dCost / temp_);</div>
<div class="line"><a name="l00197"></a><span class="lineno"> 197</span>  <span class="keywordflow">if</span> (transitionProbability > 0.5)</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>  <span class="keywordtype">double</span> costRange = worstCost_.value() - bestCost_.value();</div>
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span>  <span class="keywordflow">if</span> (fabs(costRange) > 1e-4) <span class="comment">// Do not divide by zero</span></div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  <span class="comment">// Successful transition test. Decrease the temperature slightly</span></div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  temp_ /= exp(dCost / (0.1 * costRange));</div>
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  </div>
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  <span class="keywordflow">return</span> <span class="keyword">true</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>  </div>
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  <span class="comment">// The transition failed. Increase the temperature (slightly)</span></div>
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  temp_ *= tempChangeFactor_;</div>
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span> }</div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  </div>
<div class="line"><a name="l00212"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a15fc70c8b2683c10f94ebd2217cac0c9"> 212</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a15fc70c8b2683c10f94ebd2217cac0c9">ompl::geometric::BiTRRT::minExpansionControl</a>(<span class="keywordtype">double</span> dist)</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>  <span class="keywordflow">if</span> (dist > frontierThreshold_) <span class="comment">// Exploration</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>  ++frontierCount_;</div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</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="comment">// Refinement</span></div>
<div class="line"><a name="l00220"></a><span class="lineno"> 220</span>  <span class="comment">// Check the current ratio first before accepting it</span></div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span>  <span class="keywordflow">if</span> ((<span class="keywordtype">double</span>)nonfrontierCount_ / (<span class="keywordtype">double</span>)frontierCount_ > frontierNodeRatio_)</div>
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span>  <span class="keywordflow">return</span> <span class="keyword">false</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>  ++nonfrontierCount_;</div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</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>  </div>
<div class="line"><a name="l00228"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#ace1073d843ebf9969f240cc4d9887708"> 228</a></span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a24f5c91df65e5ad68c24c6d5071bbd1f">ompl::geometric::BiTRRT::GrowResult</a> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#aaf58b35ea1e00273218ad323331e228f">ompl::geometric::BiTRRT::extendTree</a>(<a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *nearest, <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> &tree,</div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *toMotion, <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *&result)</div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span> {</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  <span class="keywordtype">bool</span> reach = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span>  </div>
<div class="line"><a name="l00233"></a><span class="lineno"> 233</span>  <span class="comment">// Compute the state to extend toward</span></div>
<div class="line"><a name="l00234"></a><span class="lineno"> 234</span>  <span class="keywordtype">bool</span> treeIsStart = (tree == tStart_);</div>
<div class="line"><a name="l00235"></a><span class="lineno"> 235</span>  <span class="keywordtype">double</span> d = (treeIsStart ? si_->distance(nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>)</div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  : si_->distance(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>));</div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  <span class="comment">// Truncate the random state to be no more than maxDistance_ from nearest neighbor</span></div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  <span class="keywordflow">if</span> (d > maxDistance_)</div>
<div class="line"><a name="l00239"></a><span class="lineno"> 239</span>  {</div>
<div class="line"><a name="l00240"></a><span class="lineno"> 240</span>  <span class="keywordflow">if</span> (tree == tStart_)</div>
<div class="line"><a name="l00241"></a><span class="lineno"> 241</span>  si_->getStateSpace()->interpolate(nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, maxDistance_ / d, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>);</div>
<div class="line"><a name="l00242"></a><span class="lineno"> 242</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span>  si_->getStateSpace()->interpolate(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, 1.0 - maxDistance_ / d, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>);</div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  d = maxDistance_;</div>
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  reach = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  }</div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  </div>
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  <span class="comment">// Validating the motion</span></div>
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span>  <span class="comment">// If we are in the goal tree, we validate the motion in reverse</span></div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  <span class="comment">// si_->checkMotion assumes that the first argument is valid, so we must check this explicitly</span></div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  <span class="comment">// If the motion is valid, check the probabilistic transition test and the</span></div>
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span>  <span class="comment">// expansion control to ensure high quality nodes are added.</span></div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span>  <span class="keywordtype">bool</span> validMotion =</div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  (tree == tStart_ ? si_->checkMotion(nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>) :</div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  si_->isValid(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>) && si_->checkMotion(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>)) &&</div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  transitionTest(tree == tStart_ ? opt_->motionCost(nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>)</div>
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span>  : opt_->motionCost(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>)) &&</div>
<div class="line"><a name="l00258"></a><span class="lineno"> 258</span>  minExpansionControl(d);</div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  </div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span>  <span class="keywordflow">if</span> (validMotion)</div>
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  {</div>
<div class="line"><a name="l00262"></a><span class="lineno"> 262</span>  result = addMotion(toMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, tree, nearest);</div>
<div class="line"><a name="l00263"></a><span class="lineno"> 263</span>  <span class="keywordflow">return</span> reach ? SUCCESS : ADVANCED;</div>
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  }</div>
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  </div>
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  <span class="keywordflow">return</span> FAILED;</div>
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span> }</div>
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span>  </div>
<div class="line"><a name="l00269"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#aaf58b35ea1e00273218ad323331e228f"> 269</a></span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a24f5c91df65e5ad68c24c6d5071bbd1f">ompl::geometric::BiTRRT::GrowResult</a> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#aaf58b35ea1e00273218ad323331e228f">ompl::geometric::BiTRRT::extendTree</a>(<a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *toMotion, <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> &tree,</div>
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *&result)</div>
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span> {</div>
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span>  <span class="comment">// Nearest neighbor</span></div>
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *nearest = tree->nearest(toMotion);</div>
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span>  <span class="keywordflow">return</span> extendTree(nearest, tree, toMotion, result);</div>
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span> }</div>
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  </div>
<div class="line"><a name="l00277"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#a7ac37e56b8f5363566c445330867efa2"> 277</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a7ac37e56b8f5363566c445330867efa2">ompl::geometric::BiTRRT::connectTrees</a>(<a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *nmotion, <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> &tree, <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *xmotion)</div>
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span> {</div>
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  <span class="comment">// Get the nearest state to nmotion in tree (nmotion is NOT in tree)</span></div>
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *nearest = tree->nearest(nmotion);</div>
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  <span class="keywordtype">bool</span> treeIsStart = tree == tStart_;</div>
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  <span class="keywordtype">double</span> dist = (treeIsStart ? si_->distance(nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>)</div>
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  : si_->distance(nmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nearest-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>));</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>  <span class="comment">// Do not attempt a connection if the trees are far apart</span></div>
<div class="line"><a name="l00286"></a><span class="lineno"> 286</span>  <span class="keywordflow">if</span> (dist > connectionRange_)</div>
<div class="line"><a name="l00287"></a><span class="lineno"> 287</span>  <span class="keywordflow">return</span> <span class="keyword">false</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>  <span class="comment">// Copy the resulting state into our scratch space</span></div>
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span>  si_->copyState(xmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>, nmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>);</div>
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  </div>
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span>  <span class="comment">// Do not try to connect states directly. Must chop up the</span></div>
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  <span class="comment">// extension into segments, just in case one piece fails</span></div>
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span>  <span class="comment">// the transition test</span></div>
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a24f5c91df65e5ad68c24c6d5071bbd1f">GrowResult</a> result;</div>
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *next = <span class="keyword">nullptr</span>;</div>
<div class="line"><a name="l00297"></a><span class="lineno"> 297</span>  <span class="keywordflow">do</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"> 299</span>  <span class="comment">// Extend tree from nearest toward xmotion</span></div>
<div class="line"><a name="l00300"></a><span class="lineno"> 300</span>  <span class="comment">// Store the result into next</span></div>
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span>  <span class="comment">// This function MAY trash xmotion</span></div>
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span>  result = extendTree(nearest, tree, xmotion, next);</div>
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span>  </div>
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span>  <span class="keywordflow">if</span> (result == ADVANCED)</div>
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span>  {</div>
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span>  nearest = next;</div>
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span>  </div>
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span>  <span class="comment">// xmotion may get trashed during extension, so we reload it here</span></div>
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span>  si_->copyState(xmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>,</div>
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span>  nmotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>); <span class="comment">// xmotion may get trashed during extension, so we reload it here</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">while</span> (result == ADVANCED);</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="comment">// Successful connection</span></div>
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span>  <span class="keywordflow">if</span> (result == SUCCESS)</div>
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span>  {</div>
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *startMotion = treeIsStart ? next : nmotion;</div>
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *goalMotion = treeIsStart ? nmotion : next;</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>  <span class="comment">// Make sure start-goal pair is valid</span></div>
<div class="line"><a name="l00321"></a><span class="lineno"> 321</span>  <span class="keywordflow">if</span> (pdef_->getGoal()->isStartGoalPairValid(startMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a>, goalMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a>))</div>
<div class="line"><a name="l00322"></a><span class="lineno"> 322</span>  {</div>
<div class="line"><a name="l00323"></a><span class="lineno"> 323</span>  <span class="comment">// Since we have connected, nmotion->state and next->state have the same value</span></div>
<div class="line"><a name="l00324"></a><span class="lineno"> 324</span>  <span class="comment">// We need to check one of their parents to avoid a duplicate state in the solution path</span></div>
<div class="line"><a name="l00325"></a><span class="lineno"> 325</span>  <span class="comment">// One of these must be true, since we do not ever attempt to connect start and goal directly.</span></div>
<div class="line"><a name="l00326"></a><span class="lineno"> 326</span>  <span class="keywordflow">if</span> (startMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">parent</a> != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00327"></a><span class="lineno"> 327</span>  startMotion = startMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">parent</a>;</div>
<div class="line"><a name="l00328"></a><span class="lineno"> 328</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00329"></a><span class="lineno"> 329</span>  goalMotion = goalMotion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">parent</a>;</div>
<div class="line"><a name="l00330"></a><span class="lineno"> 330</span>  </div>
<div class="line"><a name="l00331"></a><span class="lineno"> 331</span>  connectionPoint_ = std::make_pair(startMotion, goalMotion);</div>
<div class="line"><a name="l00332"></a><span class="lineno"> 332</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00333"></a><span class="lineno"> 333</span>  }</div>
<div class="line"><a name="l00334"></a><span class="lineno"> 334</span>  }</div>
<div class="line"><a name="l00335"></a><span class="lineno"> 335</span>  </div>
<div class="line"><a name="l00336"></a><span class="lineno"> 336</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00337"></a><span class="lineno"> 337</span> }</div>
<div class="line"><a name="l00338"></a><span class="lineno"> 338</span>  </div>
<div class="line"><a name="l00339"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#ad8b78d234a6aaf01e0a76f57fb63f583"> 339</a></span> <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#ad8b78d234a6aaf01e0a76f57fb63f583">ompl::geometric::BiTRRT::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="l00340"></a><span class="lineno"> 340</span> {</div>
<div class="line"><a name="l00341"></a><span class="lineno"> 341</span>  <span class="comment">// Basic error checking</span></div>
<div class="line"><a name="l00342"></a><span class="lineno"> 342</span>  checkValidity();</div>
<div class="line"><a name="l00343"></a><span class="lineno"> 343</span>  </div>
<div class="line"><a name="l00344"></a><span class="lineno"> 344</span>  <span class="comment">// Goal information</span></div>
<div class="line"><a name="l00345"></a><span class="lineno"> 345</span>  <a class="code" href="classompl_1_1base_1_1Goal.html">base::Goal</a> *goal = pdef_->getGoal().get();</div>
<div class="line"><a name="l00346"></a><span class="lineno"> 346</span>  <span class="keyword">auto</span> *gsr = <span class="keyword">dynamic_cast<</span><a class="code" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *<span class="keyword">></span>(goal);</div>
<div class="line"><a name="l00347"></a><span class="lineno"> 347</span>  </div>
<div class="line"><a name="l00348"></a><span class="lineno"> 348</span>  <span class="keywordflow">if</span> (gsr == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00349"></a><span class="lineno"> 349</span>  {</div>
<div class="line"><a name="l00350"></a><span class="lineno"> 350</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Goal object does not derive from GoalSampleableRegion"</span>, getName().c_str());</div>
<div class="line"><a name="l00351"></a><span class="lineno"> 351</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="l00352"></a><span class="lineno"> 352</span>  }</div>
<div class="line"><a name="l00353"></a><span class="lineno"> 353</span>  </div>
<div class="line"><a name="l00354"></a><span class="lineno"> 354</span>  <span class="comment">// Loop through the (valid) input states and add them to the start tree</span></div>
<div class="line"><a name="l00355"></a><span class="lineno"> 355</span>  <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *state = pis_.nextStart())</div>
<div class="line"><a name="l00356"></a><span class="lineno"> 356</span>  {</div>
<div class="line"><a name="l00357"></a><span class="lineno"> 357</span>  <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00358"></a><span class="lineno"> 358</span>  si_->copyState(motion->state, state);</div>
<div class="line"><a name="l00359"></a><span class="lineno"> 359</span>  motion->cost = opt_->stateCost(motion->state);</div>
<div class="line"><a name="l00360"></a><span class="lineno"> 360</span>  motion->root = motion->state; <span class="comment">// this state is the root of a tree</span></div>
<div class="line"><a name="l00361"></a><span class="lineno"> 361</span>  </div>
<div class="line"><a name="l00362"></a><span class="lineno"> 362</span>  <span class="keywordflow">if</span> (tStart_->size() == 0) <span class="comment">// do not overwrite best/worst from a prior call to solve</span></div>
<div class="line"><a name="l00363"></a><span class="lineno"> 363</span>  worstCost_ = bestCost_ = motion->cost;</div>
<div class="line"><a name="l00364"></a><span class="lineno"> 364</span>  </div>
<div class="line"><a name="l00365"></a><span class="lineno"> 365</span>  <span class="comment">// Add start motion to the tree</span></div>
<div class="line"><a name="l00366"></a><span class="lineno"> 366</span>  tStart_->add(motion);</div>
<div class="line"><a name="l00367"></a><span class="lineno"> 367</span>  }</div>
<div class="line"><a name="l00368"></a><span class="lineno"> 368</span>  </div>
<div class="line"><a name="l00369"></a><span class="lineno"> 369</span>  <span class="keywordflow">if</span> (tStart_->size() == 0)</div>
<div class="line"><a name="l00370"></a><span class="lineno"> 370</span>  {</div>
<div class="line"><a name="l00371"></a><span class="lineno"> 371</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Start tree has no valid states!"</span>, getName().c_str());</div>
<div class="line"><a name="l00372"></a><span class="lineno"> 372</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="l00373"></a><span class="lineno"> 373</span>  }</div>
<div class="line"><a name="l00374"></a><span class="lineno"> 374</span>  </div>
<div class="line"><a name="l00375"></a><span class="lineno"> 375</span>  <span class="comment">// Do the same for the goal tree, if it is empty, but only once</span></div>
<div class="line"><a name="l00376"></a><span class="lineno"> 376</span>  <span class="keywordflow">if</span> (tGoal_->size() == 0)</div>
<div class="line"><a name="l00377"></a><span class="lineno"> 377</span>  {</div>
<div class="line"><a name="l00378"></a><span class="lineno"> 378</span>  <span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *state = pis_.nextGoal(ptc);</div>
<div class="line"><a name="l00379"></a><span class="lineno"> 379</span>  <span class="keywordflow">if</span> (state != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00380"></a><span class="lineno"> 380</span>  {</div>
<div class="line"><a name="l00381"></a><span class="lineno"> 381</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *motion = addMotion(state, tGoal_);</div>
<div class="line"><a name="l00382"></a><span class="lineno"> 382</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a> = motion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>; <span class="comment">// this state is the root of a tree</span></div>
<div class="line"><a name="l00383"></a><span class="lineno"> 383</span>  }</div>
<div class="line"><a name="l00384"></a><span class="lineno"> 384</span>  }</div>
<div class="line"><a name="l00385"></a><span class="lineno"> 385</span>  </div>
<div class="line"><a name="l00386"></a><span class="lineno"> 386</span>  <span class="keywordflow">if</span> (tGoal_->size() == 0)</div>
<div class="line"><a name="l00387"></a><span class="lineno"> 387</span>  {</div>
<div class="line"><a name="l00388"></a><span class="lineno"> 388</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Goal tree has no valid states!"</span>, getName().c_str());</div>
<div class="line"><a name="l00389"></a><span class="lineno"> 389</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="l00390"></a><span class="lineno"> 390</span>  }</div>
<div class="line"><a name="l00391"></a><span class="lineno"> 391</span>  </div>
<div class="line"><a name="l00392"></a><span class="lineno"> 392</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Planning started with %d states already in datastructure"</span>, getName().c_str(),</div>
<div class="line"><a name="l00393"></a><span class="lineno"> 393</span>  (<span class="keywordtype">int</span>)(tStart_->size() + tGoal_->size()));</div>
<div class="line"><a name="l00394"></a><span class="lineno"> 394</span>  </div>
<div class="line"><a name="l00395"></a><span class="lineno"> 395</span>  base::StateSamplerPtr sampler = si_->allocStateSampler();</div>
<div class="line"><a name="l00396"></a><span class="lineno"> 396</span>  </div>
<div class="line"><a name="l00397"></a><span class="lineno"> 397</span>  <span class="keyword">auto</span> *rmotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00398"></a><span class="lineno"> 398</span>  <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *rstate = rmotion->state;</div>
<div class="line"><a name="l00399"></a><span class="lineno"> 399</span>  </div>
<div class="line"><a name="l00400"></a><span class="lineno"> 400</span>  <span class="keyword">auto</span> *xmotion = <span class="keyword">new</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a>(si_);</div>
<div class="line"><a name="l00401"></a><span class="lineno"> 401</span>  <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *xstate = xmotion->state;</div>
<div class="line"><a name="l00402"></a><span class="lineno"> 402</span>  </div>
<div class="line"><a name="l00403"></a><span class="lineno"> 403</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> tree = tStart_;</div>
<div class="line"><a name="l00404"></a><span class="lineno"> 404</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">TreeData</a> otherTree = tGoal_;</div>
<div class="line"><a name="l00405"></a><span class="lineno"> 405</span>  </div>
<div class="line"><a name="l00406"></a><span class="lineno"> 406</span>  <span class="keywordtype">bool</span> solved = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00407"></a><span class="lineno"> 407</span>  <span class="comment">// Planning loop</span></div>
<div class="line"><a name="l00408"></a><span class="lineno"> 408</span>  <span class="keywordflow">while</span> (!ptc)</div>
<div class="line"><a name="l00409"></a><span class="lineno"> 409</span>  {</div>
<div class="line"><a name="l00410"></a><span class="lineno"> 410</span>  <span class="comment">// Check if there are more goal states</span></div>
<div class="line"><a name="l00411"></a><span class="lineno"> 411</span>  <span class="keywordflow">if</span> (pis_.getSampledGoalsCount() < tGoal_->size() / 2)</div>
<div class="line"><a name="l00412"></a><span class="lineno"> 412</span>  {</div>
<div class="line"><a name="l00413"></a><span class="lineno"> 413</span>  <span class="keywordflow">if</span> (<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1State.html">base::State</a> *state = pis_.nextGoal())</div>
<div class="line"><a name="l00414"></a><span class="lineno"> 414</span>  {</div>
<div class="line"><a name="l00415"></a><span class="lineno"> 415</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *motion = addMotion(state, tGoal_);</div>
<div class="line"><a name="l00416"></a><span class="lineno"> 416</span>  motion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">root</a> = motion-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">state</a>; <span class="comment">// this state is the root of a tree</span></div>
<div class="line"><a name="l00417"></a><span class="lineno"> 417</span>  }</div>
<div class="line"><a name="l00418"></a><span class="lineno"> 418</span>  }</div>
<div class="line"><a name="l00419"></a><span class="lineno"> 419</span>  </div>
<div class="line"><a name="l00420"></a><span class="lineno"> 420</span>  <span class="comment">// Sample a state uniformly at random</span></div>
<div class="line"><a name="l00421"></a><span class="lineno"> 421</span>  sampler->sampleUniform(rstate);</div>
<div class="line"><a name="l00422"></a><span class="lineno"> 422</span>  </div>
<div class="line"><a name="l00423"></a><span class="lineno"> 423</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *result; <span class="comment">// the motion that gets added in extendTree</span></div>
<div class="line"><a name="l00424"></a><span class="lineno"> 424</span>  <span class="keywordflow">if</span> (extendTree(rmotion, tree, result) != FAILED) <span class="comment">// we added something new to the tree</span></div>
<div class="line"><a name="l00425"></a><span class="lineno"> 425</span>  {</div>
<div class="line"><a name="l00426"></a><span class="lineno"> 426</span>  <span class="comment">// Try to connect the other tree to the node we just added</span></div>
<div class="line"><a name="l00427"></a><span class="lineno"> 427</span>  <span class="keywordflow">if</span> (connectTrees(result, otherTree, xmotion))</div>
<div class="line"><a name="l00428"></a><span class="lineno"> 428</span>  {</div>
<div class="line"><a name="l00429"></a><span class="lineno"> 429</span>  <span class="comment">// The trees have been connected. Construct the solution path</span></div>
<div class="line"><a name="l00430"></a><span class="lineno"> 430</span>  <a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">Motion</a> *solution = connectionPoint_.first;</div>
<div class="line"><a name="l00431"></a><span class="lineno"> 431</span>  std::vector<Motion *> mpath1;</div>
<div class="line"><a name="l00432"></a><span class="lineno"> 432</span>  <span class="keywordflow">while</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00433"></a><span class="lineno"> 433</span>  {</div>
<div class="line"><a name="l00434"></a><span class="lineno"> 434</span>  mpath1.push_back(solution);</div>
<div class="line"><a name="l00435"></a><span class="lineno"> 435</span>  solution = solution-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">parent</a>;</div>
<div class="line"><a name="l00436"></a><span class="lineno"> 436</span>  }</div>
<div class="line"><a name="l00437"></a><span class="lineno"> 437</span>  </div>
<div class="line"><a name="l00438"></a><span class="lineno"> 438</span>  solution = connectionPoint_.second;</div>
<div class="line"><a name="l00439"></a><span class="lineno"> 439</span>  std::vector<Motion *> mpath2;</div>
<div class="line"><a name="l00440"></a><span class="lineno"> 440</span>  <span class="keywordflow">while</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00441"></a><span class="lineno"> 441</span>  {</div>
<div class="line"><a name="l00442"></a><span class="lineno"> 442</span>  mpath2.push_back(solution);</div>
<div class="line"><a name="l00443"></a><span class="lineno"> 443</span>  solution = solution-><a class="code" href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">parent</a>;</div>
<div class="line"><a name="l00444"></a><span class="lineno"> 444</span>  }</div>
<div class="line"><a name="l00445"></a><span class="lineno"> 445</span>  </div>
<div class="line"><a name="l00446"></a><span class="lineno"> 446</span>  <span class="keyword">auto</span> path(std::make_shared<PathGeometric>(si_));</div>
<div class="line"><a name="l00447"></a><span class="lineno"> 447</span>  path->getStates().reserve(mpath1.size() + mpath2.size());</div>
<div class="line"><a name="l00448"></a><span class="lineno"> 448</span>  <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath1.size() - 1; i >= 0; --i)</div>
<div class="line"><a name="l00449"></a><span class="lineno"> 449</span>  path->append(mpath1[i]->state);</div>
<div class="line"><a name="l00450"></a><span class="lineno"> 450</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &i : mpath2)</div>
<div class="line"><a name="l00451"></a><span class="lineno"> 451</span>  path->append(i->state);</div>
<div class="line"><a name="l00452"></a><span class="lineno"> 452</span>  </div>
<div class="line"><a name="l00453"></a><span class="lineno"> 453</span>  pdef_->addSolutionPath(path, <span class="keyword">false</span>, 0.0, getName());</div>
<div class="line"><a name="l00454"></a><span class="lineno"> 454</span>  solved = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00455"></a><span class="lineno"> 455</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00456"></a><span class="lineno"> 456</span>  }</div>
<div class="line"><a name="l00457"></a><span class="lineno"> 457</span>  }</div>
<div class="line"><a name="l00458"></a><span class="lineno"> 458</span>  </div>
<div class="line"><a name="l00459"></a><span class="lineno"> 459</span>  std::swap(tree, otherTree);</div>
<div class="line"><a name="l00460"></a><span class="lineno"> 460</span>  }</div>
<div class="line"><a name="l00461"></a><span class="lineno"> 461</span>  </div>
<div class="line"><a name="l00462"></a><span class="lineno"> 462</span>  si_->freeState(rstate);</div>
<div class="line"><a name="l00463"></a><span class="lineno"> 463</span>  si_->freeState(xstate);</div>
<div class="line"><a name="l00464"></a><span class="lineno"> 464</span>  <span class="keyword">delete</span> rmotion;</div>
<div class="line"><a name="l00465"></a><span class="lineno"> 465</span>  <span class="keyword">delete</span> xmotion;</div>
<div class="line"><a name="l00466"></a><span class="lineno"> 466</span>  </div>
<div class="line"><a name="l00467"></a><span class="lineno"> 467</span>  <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="l00468"></a><span class="lineno"> 468</span>  tStart_->size(), tGoal_->size());</div>
<div class="line"><a name="l00469"></a><span class="lineno"> 469</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="l00470"></a><span class="lineno"> 470</span> }</div>
<div class="line"><a name="l00471"></a><span class="lineno"> 471</span>  </div>
<div class="line"><a name="l00472"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1BiTRRT.html#ac0fd912a3b9f9d1f82a22b3f22b18daf"> 472</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1geometric_1_1BiTRRT.html#ac0fd912a3b9f9d1f82a22b3f22b18daf">ompl::geometric::BiTRRT::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="l00473"></a><span class="lineno"> 473</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00474"></a><span class="lineno"> 474</span>  Planner::getPlannerData(data);</div>
<div class="line"><a name="l00475"></a><span class="lineno"> 475</span>  </div>
<div class="line"><a name="l00476"></a><span class="lineno"> 476</span>  std::vector<Motion *> motions;</div>
<div class="line"><a name="l00477"></a><span class="lineno"> 477</span>  <span class="keywordflow">if</span> (tStart_)</div>
<div class="line"><a name="l00478"></a><span class="lineno"> 478</span>  tStart_->list(motions);</div>
<div class="line"><a name="l00479"></a><span class="lineno"> 479</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a name="l00480"></a><span class="lineno"> 480</span>  {</div>
<div class="line"><a name="l00481"></a><span class="lineno"> 481</span>  <span class="keywordflow">if</span> (motion->parent == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00482"></a><span class="lineno"> 482</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="l00483"></a><span class="lineno"> 483</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00484"></a><span class="lineno"> 484</span>  {</div>
<div class="line"><a name="l00485"></a><span class="lineno"> 485</span>  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="l00486"></a><span class="lineno"> 486</span>  }</div>
<div class="line"><a name="l00487"></a><span class="lineno"> 487</span>  }</div>
<div class="line"><a name="l00488"></a><span class="lineno"> 488</span>  </div>
<div class="line"><a name="l00489"></a><span class="lineno"> 489</span>  motions.clear();</div>
<div class="line"><a name="l00490"></a><span class="lineno"> 490</span>  <span class="keywordflow">if</span> (tGoal_)</div>
<div class="line"><a name="l00491"></a><span class="lineno"> 491</span>  tGoal_->list(motions);</div>
<div class="line"><a name="l00492"></a><span class="lineno"> 492</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a name="l00493"></a><span class="lineno"> 493</span>  {</div>
<div class="line"><a name="l00494"></a><span class="lineno"> 494</span>  <span class="keywordflow">if</span> (motion->parent == <span class="keyword">nullptr</span>)</div>
<div class="line"><a name="l00495"></a><span class="lineno"> 495</span>  data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a3604cb85b0402b09b319c5f1df02b12e">addGoalVertex</a>(<a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state, 2));</div>
<div class="line"><a name="l00496"></a><span class="lineno"> 496</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00497"></a><span class="lineno"> 497</span>  {</div>
<div class="line"><a name="l00498"></a><span class="lineno"> 498</span>  <span class="comment">// The edges in the goal tree are reversed to be consistent with start tree</span></div>
<div class="line"><a name="l00499"></a><span class="lineno"> 499</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->state, 2), <a class="code" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->parent->state, 2));</div>
<div class="line"><a name="l00500"></a><span class="lineno"> 500</span>  }</div>
<div class="line"><a name="l00501"></a><span class="lineno"> 501</span>  }</div>
<div class="line"><a name="l00502"></a><span class="lineno"> 502</span>  </div>
<div class="line"><a name="l00503"></a><span class="lineno"> 503</span>  <span class="comment">// Add the edge connecting the two trees</span></div>
<div class="line"><a name="l00504"></a><span class="lineno"> 504</span>  <span class="keywordflow">if</span> ((connectionPoint_.first != <span class="keyword">nullptr</span>) && (connectionPoint_.second != <span class="keyword">nullptr</span>))</div>
<div class="line"><a name="l00505"></a><span class="lineno"> 505</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->state), data.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a06792592713e6463c4b9814f2a715b4c">vertexIndex</a>(connectionPoint_.second->state));</div>
<div class="line"><a name="l00506"></a><span class="lineno"> 506</span> }</div>
</div><!-- fragment --></div><!-- contents -->
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a2f3d18a363976e7345cbc28577018766"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a2f3d18a363976e7345cbc28577018766">ompl::geometric::BiTRRT::BiTRRT</a></div><div class="ttdeci">BiTRRT(const base::SpaceInformationPtr &si)</div><div class="ttdoc">Constructor.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00045">BiTRRT.cpp:45</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a242985410fb727f691033a274f400c9c"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a242985410fb727f691033a274f400c9c">ompl::geometric::BiTRRT::getFrontierNodeRatio</a></div><div class="ttdeci">double getFrontierNodeRatio() const</div><div class="ttdoc">Get the ratio between adding non-frontier nodes to frontier nodes.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00260">BiTRRT.h:260</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_ad71f5b6833006f7e7fc008c51428d9bf"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#ad71f5b6833006f7e7fc008c51428d9bf">ompl::geometric::BiTRRT::setRange</a></div><div class="ttdeci">void setRange(double distance)</div><div class="ttdoc">Set the maximum possible length of any one motion in the search tree. Very short/long motions may inh...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00179">BiTRRT.h:179</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_1geometric_1_1BiTRRT_html_a10a681d8fb04bc7250f2648b0206599e"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a10a681d8fb04bc7250f2648b0206599e">ompl::geometric::BiTRRT::transitionTest</a></div><div class="ttdeci">bool transitionTest(const base::Cost &motionCost)</div><div class="ttdoc">Transition test that filters transitions based on the motion cost. If the motion cost is near or belo...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00185">BiTRRT.cpp:185</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_1BiTRRT_html_af01edc2564a947c534f77011027826c2"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#af01edc2564a947c534f77011027826c2">ompl::geometric::BiTRRT::setInitTemperature</a></div><div class="ttdeci">void setInitTemperature(double initTemperature)</div><div class="ttdoc">Set the initial temperature at the start of planning. Should be high to allow for initial exploration...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00225">BiTRRT.h:225</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a161724203e2d0ef60e38fe4237835ac4"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a161724203e2d0ef60e38fe4237835ac4">ompl::geometric::BiTRRT::setFrontierNodeRatio</a></div><div class="ttdeci">void setFrontierNodeRatio(double frontierNodeRatio)</div><div class="ttdoc">Set the ratio between adding non-frontier nodes to frontier nodes. For example: .1 is one non-frontie...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00253">BiTRRT.h:253</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_1_1Motion_html_aa6405768e8f5ceee5bdfc73b8eed47aa"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#aa6405768e8f5ceee5bdfc73b8eed47aa">ompl::geometric::BiTRRT::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 contained in.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00303">BiTRRT.h:303</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_1_1Motion_html_a7ddfbdd700ef6024063446c542b6e295"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a7ddfbdd700ef6024063446c542b6e295">ompl::geometric::BiTRRT::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="BiTRRT_8h_source.html#l00296">BiTRRT.h:296</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_aaa69d535612c856c194f0664eb0c08a2"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#aaa69d535612c856c194f0664eb0c08a2">ompl::geometric::BiTRRT::getFrontierThreshold</a></div><div class="ttdeci">double getFrontierThreshold() const</div><div class="ttdoc">Get the distance between a new state and the nearest neighbor that qualifies a state as being a front...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00245">BiTRRT.h:245</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1State_html"><div class="ttname"><a href="classompl_1_1base_1_1State.html">ompl::base::State</a></div><div class="ttdoc">Definition of an abstract state.</div><div class="ttdef"><b>Definition:</b> <a href="base_2State_8h_source.html#l00113">State.h:113</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_aaf58b35ea1e00273218ad323331e228f"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#aaf58b35ea1e00273218ad323331e228f">ompl::geometric::BiTRRT::extendTree</a></div><div class="ttdeci">GrowResult extendTree(Motion *toMotion, TreeData &tree, Motion *&result)</div><div class="ttdoc">Extend tree toward the state in rmotion. Store the result of the extension, if any,...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00269">BiTRRT.cpp:269</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#l00122">SelfConfig.h:122</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a15fc70c8b2683c10f94ebd2217cac0c9"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a15fc70c8b2683c10f94ebd2217cac0c9">ompl::geometric::BiTRRT::minExpansionControl</a></div><div class="ttdeci">bool minExpansionControl(double dist)</div><div class="ttdoc">Use frontier node ratio to filter nodes that do not add new information to the search tree.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00212">BiTRRT.cpp:212</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_1_1Motion_html_a159061928e5d93bef2bbad25a19c00fd"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html#a159061928e5d93bef2bbad25a19c00fd">ompl::geometric::BiTRRT::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="BiTRRT_8h_source.html#l00293">BiTRRT.h:293</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Cost_html_a3cd5c47c10a591badea945b4fc84014c"><div class="ttname"><a href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">ompl::base::Cost::value</a></div><div class="ttdeci">double value() const</div><div class="ttdoc">The value of the cost.</div><div class="ttdef"><b>Definition:</b> <a href="Cost_8h_source.html#l00152">Cost.h:152</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Cost_html"><div class="ttname"><a href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a></div><div class="ttdoc">Definition of a cost value. Can represent the cost of a motion or the cost of a state.</div><div class="ttdef"><b>Definition:</b> <a href="Cost_8h_source.html#l00111">Cost.h:111</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_1BiTRRT_html_a6c900b2bbcfe22d0817928b1be743d5f"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a6c900b2bbcfe22d0817928b1be743d5f">ompl::geometric::BiTRRT::addMotion</a></div><div class="ttdeci">Motion * addMotion(const base::State *state, TreeData &tree, Motion *parent=nullptr)</div><div class="ttdoc">Add a state to the given tree. The motion created is returned.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00166">BiTRRT.cpp:166</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a28456d8d144a225f25db1426822432f1"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a28456d8d144a225f25db1426822432f1">ompl::geometric::BiTRRT::getInitTemperature</a></div><div class="ttdeci">double getInitTemperature() const</div><div class="ttdoc">Get the initial temperature at the start of planning.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00231">BiTRRT.h:231</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a7ac37e56b8f5363566c445330867efa2"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a7ac37e56b8f5363566c445330867efa2">ompl::geometric::BiTRRT::connectTrees</a></div><div class="ttdeci">bool connectTrees(Motion *nmotion, TreeData &tree, Motion *xmotion)</div><div class="ttdoc">Attempt to connect tree to nmotion, which is in the other tree. xmotion is scratch space and will be ...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00277">BiTRRT.cpp:277</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_ad8b78d234a6aaf01e0a76f57fb63f583"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#ad8b78d234a6aaf01e0a76f57fb63f583">ompl::geometric::BiTRRT::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="BiTRRT_8cpp_source.html#l00339">BiTRRT.cpp:339</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_ac0fd912a3b9f9d1f82a22b3f22b18daf"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#ac0fd912a3b9f9d1f82a22b3f22b18daf">ompl::geometric::BiTRRT::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="BiTRRT_8cpp_source.html#l00472">BiTRRT.cpp:472</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_ac63536fa52ee81830fdaad13364c8c21"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#ac63536fa52ee81830fdaad13364c8c21">ompl::geometric::BiTRRT::freeMemory</a></div><div class="ttdeci">void freeMemory()</div><div class="ttdoc">Free all memory allocated during planning.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8cpp_source.html#l00070">BiTRRT.cpp:70</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_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#l00313">PlannerData.cpp:313</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_1BiTRRT_html_a7d06fd3929104c9dca2a743b1f4cbddc"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a7d06fd3929104c9dca2a743b1f4cbddc">ompl::geometric::BiTRRT::setTempChangeFactor</a></div><div class="ttdeci">void setTempChangeFactor(double factor)</div><div class="ttdoc">Set the factor by which the temperature is increased after a failed transition test....</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00195">BiTRRT.h:195</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a8f7bbe64f7b08b9c986f189339ceb2d1"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a8f7bbe64f7b08b9c986f189339ceb2d1">ompl::geometric::BiTRRT::setCostThreshold</a></div><div class="ttdeci">void setCostThreshold(double maxCost)</div><div class="ttdoc">Set the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00210">BiTRRT.h:210</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_1BiTRRT_html_a24f5c91df65e5ad68c24c6d5071bbd1f"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a24f5c91df65e5ad68c24c6d5071bbd1f">ompl::geometric::BiTRRT::GrowResult</a></div><div class="ttdeci">GrowResult</div><div class="ttdoc">The result of a call to extendTree.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00328">BiTRRT.h:328</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a2376b591508ad0543c531e7dac06a426"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a2376b591508ad0543c531e7dac06a426">ompl::geometric::BiTRRT::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="BiTRRT_8cpp_source.html#l00097">BiTRRT.cpp:97</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Goal_html"><div class="ttname"><a href="classompl_1_1base_1_1Goal.html">ompl::base::Goal</a></div><div class="ttdoc">Abstract definition of goals.</div><div class="ttdef"><b>Definition:</b> <a href="Goal_8h_source.html#l00126">Goal.h:126</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_1BiTRRT_html_afc2441e4deb2cf71c680db8838ab2ff8"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#afc2441e4deb2cf71c680db8838ab2ff8">ompl::geometric::BiTRRT::getTempChangeFactor</a></div><div class="ttdeci">double getTempChangeFactor() const</div><div class="ttdoc">Get the factor by which the temperature is increased after a failed transition.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00202">BiTRRT.h:202</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#l00411">PlannerData.cpp:411</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_ae2aabb326b63edc54d73ae640a8a8515"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#ae2aabb326b63edc54d73ae640a8a8515">ompl::geometric::BiTRRT::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="BiTRRT_8h_source.html#l00185">BiTRRT.h:185</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#l00430">PlannerData.cpp:430</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a41e787e94232d65324262af83939b50e"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a41e787e94232d65324262af83939b50e">ompl::geometric::BiTRRT::TreeData</a></div><div class="ttdeci">std::shared_ptr< NearestNeighbors< Motion * > > TreeData</div><div class="ttdoc">The nearest-neighbors data structure that contains the entire the tree of motions generated during pl...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00311">BiTRRT.h:311</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_a3604cb85b0402b09b319c5f1df02b12e"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#a3604cb85b0402b09b319c5f1df02b12e">ompl::base::PlannerData::addGoalVertex</a></div><div class="ttdeci">unsigned int addGoalVertex(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#l00420">PlannerData.cpp:420</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_1geometric_1_1BiTRRT_html_abce500ace7b425fb85c99f6f216f12d6"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#abce500ace7b425fb85c99f6f216f12d6">ompl::geometric::BiTRRT::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="BiTRRT_8cpp_source.html#l00115">BiTRRT.cpp:115</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a53f6a346df9177e79e91a6db06c7f328"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a53f6a346df9177e79e91a6db06c7f328">ompl::geometric::BiTRRT::getCostThreshold</a></div><div class="ttdeci">double getCostThreshold() const</div><div class="ttdoc">Get the cost threshold (default is infinity). Any motion cost that is not better than this cost (acco...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00218">BiTRRT.h:218</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="agroup__logging_html_ga576d0bc79b521f19c5415f330e2b173d"><div class="ttname"><a href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a></div><div class="ttdeci">#define OMPL_DEBUG(fmt,...)</div><div class="ttdoc">Log a formatted debugging string.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00070">Console.h:70</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 class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_1_1Motion_html"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT_1_1Motion.html">ompl::geometric::BiTRRT::Motion</a></div><div class="ttdoc">Representation of a motion in the search tree.</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00279">BiTRRT.h:279</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1BiTRRT_html_a21c3fa749ad83310b40988aa96357a8c"><div class="ttname"><a href="classompl_1_1geometric_1_1BiTRRT.html#a21c3fa749ad83310b40988aa96357a8c">ompl::geometric::BiTRRT::setFrontierThreshold</a></div><div class="ttdeci">void setFrontierThreshold(double frontierThreshold)</div><div class="ttdoc">Set the distance between a new state and the nearest neighbor that qualifies a state as being a front...</div><div class="ttdef"><b>Definition:</b> <a href="BiTRRT_8h_source.html#l00238">BiTRRT.h:238</a></div></div>
<div class="ttc" id="anamespaceompl_1_1magic_html_a3c9c3d6c0ee87fea2dbc5fa7484d15fa"><div class="ttname"><a href="namespaceompl_1_1magic.html#a3c9c3d6c0ee87fea2dbc5fa7484d15fa">ompl::magic::COST_MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION</a></div><div class="ttdeci">static const double COST_MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION</div><div class="ttdoc">For cost-based planners it has been observed that smaller ranges are typically suitable....</div><div class="ttdef"><b>Definition:</b> <a href="MagicConstants_8h_source.html#l00143">MagicConstants.h:143</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>