-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathATRRT_8cpp_source.html
More file actions
809 lines (807 loc) · 151 KB
/
ATRRT_8cpp_source.html
File metadata and controls
809 lines (807 loc) · 151 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
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
<!-- HTML header for doxygen 1.14.0-->
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US" class="light-mode">
<head>
<meta name="color-scheme" content="light">
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
<meta name="generator" content="Doxygen 1.16.1"/>
<meta name="viewport" content="width=device-width, initial-scale=1"/>
<title>ompl: ompl/geometric/planners/rrt/src/ATRRT.cpp Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="jquery.js"></script>
<script type="text/javascript" src="dynsections.js"></script>
<script type="text/javascript" src="clipboard.js"></script>
<script type="text/javascript" src="cookie.js"></script>
<link href="search/search.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="search/searchdata.js"></script>
<script type="text/javascript" src="search/search.js"></script>
<script type="text/javascript">
$(function() { init_search(); });
</script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
<link href="ompl.css" rel="stylesheet" type="text/css"/>
<link rel="stylesheet" href="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/css/bootstrap.min.css" integrity="sha384-ggOyR0iXCbMQv3Xipma34MD+dH/1fQ784/j6cY/iJTQUOhcWr7x9JvoRxT2MZw1T" crossorigin="anonymous">
<link href="ompl.css" rel="stylesheet">
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<nav class="navbar navbar-expand-md fixed-top navbar-dark">
<a class="navbar-brand" href="./index.html">OMPL</a>
<button class="navbar-toggler" type="button" data-toggle="collapse" data-target="#navbar">
<span class="navbar-toggler-icon"></span>
</button>
<div class="collapse navbar-collapse" id="navbar">
<ul class="navbar-nav mr-auto">
<li class="nav-item"><a class="nav-link" href="download.html">Download</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="docDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Documentation</a>
<div class="dropdown-menu" aria-labelledby="docDropdown">
<a class="dropdown-item" href="https://ompl.kavrakilab.org/OMPL_Primer.pdf">Primer</a>
<a class="dropdown-item" href="installation.html">Installation</a>
<a class="dropdown-item" href="tutorials.html">Tutorials</a>
<a class="dropdown-item" href="demos.html">Demos</a>
<a class="dropdown-item" href="python.html">Python Bindings</a>
<a class="dropdown-item" href="planners.html">Available Planners</a>
<a class="dropdown-item" href="plannerTerminationConditions.html">Planner Termination Conditions</a>
<a class="dropdown-item" href="benchmark.html">Benchmarking Planners</a>
<a class="dropdown-item" href="spaces.html">Available State Spaces</a>
<a class="dropdown-item" href="optimalPlanning.html">Optimal Planning</a>
<a class="dropdown-item" href="constrainedPlanning.html">Constrained Planning</a>
<a class="dropdown-item" href="multiLevelPlanning.html">Multilevel Planning</a>
<a class="dropdown-item" href="FAQ.html">FAQ</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">External links</div>
<a class="dropdown-item" href="http://moveit.ros.org">MoveIt</a>
<a class="dropdown-item" href="http://plannerarena.org">Planner Arena</a>
<a class="dropdown-item" href="https://moveit.ros.org//moveit!/ros/2013/05/07/icra-motion-planning-tutorial.html">ICRA 2013 Tutorial</a>
<a class="dropdown-item" href="http://kavrakilab.org/iros2011/">IROS 2011 Tutorial</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="gallery.html">Gallery</a></li>
<li class="nav-item"><a class="nav-link" href="integration.html">OMPL Integrations</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="codeDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Code</a>
<div class="dropdown-menu" aria-labelledby="codeDropdown">
<a class="dropdown-item" href="api_overview.html">API Overview</a>
<a class="dropdown-item" href="annotated.html">Classes</a>
<a class="dropdown-item" href="files.html">Files</a>
<a class="dropdown-item" href="styleGuide.html">Style Guide</a>
<a class="dropdown-item" href="https://github.com/ompl/ompl">OMPL on GitHub</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://github.com/ompl/ompl/issues">Issues</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="communityDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Community</a>
<div class="dropdown-menu" aria-labelledby="communityDropdown">
<a class="dropdown-item" href="support.html">Get Support</a>
<a class="dropdown-item" href="developers.html">Developers/Contributors</a>
<a class="dropdown-item" href="contrib.html">Submit a Contribution</a>
</div>
</li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="aboutDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">About</a>
<div class="dropdown-menu" aria-labelledby="aboutDropdown">
<a class="dropdown-item" href="license.html">License</a>
<a class="dropdown-item" href="citations.html">Citations</a>
<a class="dropdown-item" href="acknowledgements.html">Acknowledgments</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://ompl.kavrakilab.org/blog.html">Blog</a></li>
</ul>
<div id="MSearchBox" class="MSearchBoxInactive">
<span class="left">
<span id="MSearchSelect" class="search-icon" onmouseover="return searchBox.OnSearchSelectShow()" onmouseout="return searchBox.OnSearchSelectHide()"><span class="search-icon-dropdown"></span></span>
<input type="text" id="MSearchField" value="" placeholder="Search" accesskey="S"
onfocus="searchBox.OnSearchFieldFocus(true)"
onblur="searchBox.OnSearchFieldFocus(false)"
onkeyup="searchBox.OnSearchFieldChange(event)"/>
</span><span class="right">
<a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><div id="MSearchCloseImg" class="close-icon"></div></a>
</span>
</div>
</div>
</nav>
<div class="container" role="main">
<div>
<!-- Generated by Doxygen 1.16.1 -->
<script type="text/javascript">
var searchBox = new SearchBox("searchBox", "search/",'.html');
</script>
<script type="text/javascript">
$(function() { codefold.init(); });
</script>
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
onkeydown="return searchBox.OnSearchSelectKey(event)">
</div>
<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<div id="MSearchResults">
<div class="SRPage">
<div id="SRIndex">
<div id="SRResults"></div>
<div class="SRStatus" id="Loading">Loading...</div>
<div class="SRStatus" id="Searching">Searching...</div>
<div class="SRStatus" id="NoMatches">No Matches</div>
</div>
</div>
</div>
</div>
<div id="nav-path" class="navpath">
<ul>
<li class="navelem"><b>ompl</b></li><li class="navelem"><b>geometric</b></li><li class="navelem"><b>planners</b></li><li class="navelem"><b>rrt</b></li><li class="navelem"><b>src</b></li> </ul>
</div>
</div><!-- top -->
<div id="doc-content">
<div class="header">
<div class="headertitle"><div class="title">ATRRT.cpp</div></div>
</div><!--header-->
<div class="contents">
<div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span><span class="comment">/*********************************************************************</span></div>
<div class="line"><a id="l00002" name="l00002"></a><span class="lineno"> 2</span><span class="comment"> * Software License Agreement (BSD License)</span></div>
<div class="line"><a id="l00003" name="l00003"></a><span class="lineno"> 3</span><span class="comment"> *</span></div>
<div class="line"><a id="l00004" name="l00004"></a><span class="lineno"> 4</span><span class="comment"> * Copyright (c) 2025, Joris Chomarat</span></div>
<div class="line"><a id="l00005" name="l00005"></a><span class="lineno"> 5</span><span class="comment"> * All rights reserved.</span></div>
<div class="line"><a id="l00006" name="l00006"></a><span class="lineno"> 6</span><span class="comment"> *</span></div>
<div class="line"><a id="l00007" name="l00007"></a><span class="lineno"> 7</span><span class="comment"> * Redistribution and use in source and binary forms, with or without</span></div>
<div class="line"><a id="l00008" name="l00008"></a><span class="lineno"> 8</span><span class="comment"> * modification, are permitted provided that the following conditions</span></div>
<div class="line"><a id="l00009" name="l00009"></a><span class="lineno"> 9</span><span class="comment"> * are met:</span></div>
<div class="line"><a id="l00010" name="l00010"></a><span class="lineno"> 10</span><span class="comment"> *</span></div>
<div class="line"><a id="l00011" name="l00011"></a><span class="lineno"> 11</span><span class="comment"> * * Redistributions of source code must retain the above copyright</span></div>
<div class="line"><a id="l00012" name="l00012"></a><span class="lineno"> 12</span><span class="comment"> * notice, this list of conditions and the following disclaimer.</span></div>
<div class="line"><a id="l00013" name="l00013"></a><span class="lineno"> 13</span><span class="comment"> * * Redistributions in binary form must reproduce the above</span></div>
<div class="line"><a id="l00014" name="l00014"></a><span class="lineno"> 14</span><span class="comment"> * copyright notice, this list of conditions and the following</span></div>
<div class="line"><a id="l00015" name="l00015"></a><span class="lineno"> 15</span><span class="comment"> * disclaimer in the documentation and/or other materials provided</span></div>
<div class="line"><a id="l00016" name="l00016"></a><span class="lineno"> 16</span><span class="comment"> * with the distribution.</span></div>
<div class="line"><a id="l00017" name="l00017"></a><span class="lineno"> 17</span><span class="comment"> * * Neither the name of the copyright holder nor the names of its</span></div>
<div class="line"><a id="l00018" name="l00018"></a><span class="lineno"> 18</span><span class="comment"> * contributors may be used to endorse or promote products derived</span></div>
<div class="line"><a id="l00019" name="l00019"></a><span class="lineno"> 19</span><span class="comment"> * from this software without specific prior written permission.</span></div>
<div class="line"><a id="l00020" name="l00020"></a><span class="lineno"> 20</span><span class="comment"> *</span></div>
<div class="line"><a id="l00021" name="l00021"></a><span class="lineno"> 21</span><span class="comment"> * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span></div>
<div class="line"><a id="l00022" name="l00022"></a><span class="lineno"> 22</span><span class="comment"> * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span></div>
<div class="line"><a id="l00023" name="l00023"></a><span class="lineno"> 23</span><span class="comment"> * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span></div>
<div class="line"><a id="l00024" name="l00024"></a><span class="lineno"> 24</span><span class="comment"> * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span></div>
<div class="line"><a id="l00025" name="l00025"></a><span class="lineno"> 25</span><span class="comment"> * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span></div>
<div class="line"><a id="l00026" name="l00026"></a><span class="lineno"> 26</span><span class="comment"> * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span></div>
<div class="line"><a id="l00027" name="l00027"></a><span class="lineno"> 27</span><span class="comment"> * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span></div>
<div class="line"><a id="l00028" name="l00028"></a><span class="lineno"> 28</span><span class="comment"> * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span></div>
<div class="line"><a id="l00029" name="l00029"></a><span class="lineno"> 29</span><span class="comment"> * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span></div>
<div class="line"><a id="l00030" name="l00030"></a><span class="lineno"> 30</span><span class="comment"> * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span></div>
<div class="line"><a id="l00031" name="l00031"></a><span class="lineno"> 31</span><span class="comment"> * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span></div>
<div class="line"><a id="l00032" name="l00032"></a><span class="lineno"> 32</span><span class="comment"> * POSSIBILITY OF SUCH DAMAGE.</span></div>
<div class="line"><a id="l00033" name="l00033"></a><span class="lineno"> 33</span><span class="comment"> *********************************************************************/</span></div>
<div class="line"><a id="l00034" name="l00034"></a><span class="lineno"> 34</span> </div>
<div class="line"><a id="l00035" name="l00035"></a><span class="lineno"> 35</span><span class="comment">/* Author: Joris Chomarat */</span></div>
<div class="line"><a id="l00036" name="l00036"></a><span class="lineno"> 36</span> </div>
<div class="line"><a id="l00037" name="l00037"></a><span class="lineno"> 37</span><span class="preprocessor">#include "ompl/geometric/planners/rrt/ATRRT.h"</span></div>
<div class="line"><a id="l00038" name="l00038"></a><span class="lineno"> 38</span><span class="preprocessor">#include "ompl/base/objectives/MechanicalWorkOptimizationObjective.h"</span></div>
<div class="line"><a id="l00039" name="l00039"></a><span class="lineno"> 39</span><span class="preprocessor">#include "ompl/base/goals/GoalSampleableRegion.h"</span></div>
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"> 40</span><span class="preprocessor">#include "ompl/tools/config/SelfConfig.h"</span></div>
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"> 41</span><span class="preprocessor">#include "ompl/tools/config/MagicConstants.h"</span></div>
<div class="line"><a id="l00042" name="l00042"></a><span class="lineno"> 42</span><span class="preprocessor">#include <limits></span></div>
<div class="line"><a id="l00043" name="l00043"></a><span class="lineno"> 43</span> </div>
<div class="foldopen" id="foldopen00044" data-start="{" data-end="}">
<div class="line"><a id="l00044" name="l00044"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a2c20fbc4a2f83292f2b3fc8f3e23b4c2"> 44</a></span><a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a2c20fbc4a2f83292f2b3fc8f3e23b4c2">ompl::geometric::ATRRT::ATRRT</a>(<span class="keyword">const</span> base::SpaceInformationPtr &si) : <a class="code hl_namespace" href="namespaceompl_1_1base.html">base</a>::Planner(si, <span class="stringliteral">"ATRRT"</span>)</div>
<div class="line"><a id="l00045" name="l00045"></a><span class="lineno"> 45</span>{</div>
<div class="line"><a id="l00046" name="l00046"></a><span class="lineno"> 46</span> <span class="comment">// Standard RRT Variables</span></div>
<div class="line"><a id="l00047" name="l00047"></a><span class="lineno"> 47</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.approximateSolutions = <span class="keyword">true</span>;</div>
<div class="line"><a id="l00048" name="l00048"></a><span class="lineno"> 48</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a4311ea7a0470f0e0f76cb1656d63e365">specs_</a>.directed = <span class="keyword">true</span>;</div>
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"> 49</span> </div>
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"> 50</span> Planner::declareParam<double>(<span class="stringliteral">"range"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a525f4129d7e241219900b2b170a9f262">ATRRT::setRange</a>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#aa9678bc4ff0b83291112cbd7a3d21f87">ATRRT::getRange</a>, <span class="stringliteral">"0.:1.:10000."</span>);</div>
<div class="line"><a id="l00051" name="l00051"></a><span class="lineno"> 51</span> Planner::declareParam<double>(<span class="stringliteral">"goal_bias"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a1089e25c891776765a85f2ecec27cd2f">ATRRT::setGoalBias</a>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a329c36cd4c51bb4af3da7387e214edca">ATRRT::getGoalBias</a>, <span class="stringliteral">"0.:.05:1."</span>);</div>
<div class="line"><a id="l00052" name="l00052"></a><span class="lineno"> 52</span> </div>
<div class="line"><a id="l00053" name="l00053"></a><span class="lineno"> 53</span> <span class="comment">// ATRRT Specific Variables</span></div>
<div class="line"><a id="l00054" name="l00054"></a><span class="lineno"> 54</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">frontierThreshold_</a> = 0.0; <span class="comment">// set in setup()</span></div>
<div class="line"><a id="l00055" name="l00055"></a><span class="lineno"> 55</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#aedbccfd472c65277ddc769f030f22ede">setTempChangeFactor</a>(0.1); <span class="comment">// how much to increase the temp each time</span></div>
<div class="line"><a id="l00056" name="l00056"></a><span class="lineno"> 56</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a838a67a4af1929606ff32221de7f9fe1">costThreshold_</a> = <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a>(std::numeric_limits<double>::infinity());</div>
<div class="line"><a id="l00057" name="l00057"></a><span class="lineno"> 57</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ac190ee401a05c61192b5f7ca7b04b4d9">initTemperature_</a> = 100; <span class="comment">// where the temperature starts out</span></div>
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"> 58</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ab7ea6b5269d2e02e06387b0fa4643b37">frontierNodeRatio_</a> = 0.1; <span class="comment">// 1/10, or 1 nonfrontier for every 10 frontier</span></div>
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"> 59</span> </div>
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"> 60</span> Planner::declareParam<double>(<span class="stringliteral">"temp_change_factor"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#aedbccfd472c65277ddc769f030f22ede">ATRRT::setTempChangeFactor</a>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#aaa7b4cc7106a62f9f0f3f2c66ceba621">ATRRT::getTempChangeFactor</a>,</div>
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"> 61</span> <span class="stringliteral">"0.:.1:1."</span>);</div>
<div class="line"><a id="l00062" name="l00062"></a><span class="lineno"> 62</span> Planner::declareParam<double>(<span class="stringliteral">"init_temperature"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a27d454a5a9dbd74dbddca2a278ddbf72">ATRRT::setInitTemperature</a>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a145ead99c3474e400883c62edea2ad96">ATRRT::getInitTemperature</a>);</div>
<div class="line"><a id="l00063" name="l00063"></a><span class="lineno"> 63</span> Planner::declareParam<double>(<span class="stringliteral">"frontier_threshold"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a7c5d3ef6b42f04b9055f00a6de3f47c5">ATRRT::setFrontierThreshold</a>,</div>
<div class="line"><a id="l00064" name="l00064"></a><span class="lineno"> 64</span> &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a4052ff76eb08eaad5778c8068f1be913">ATRRT::getFrontierThreshold</a>);</div>
<div class="line"><a id="l00065" name="l00065"></a><span class="lineno"> 65</span> Planner::declareParam<double>(<span class="stringliteral">"frontier_node_ratio"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ac4176262e320e87b3d71789e28615b10">ATRRT::setFrontierNodeRatio</a>,</div>
<div class="line"><a id="l00066" name="l00066"></a><span class="lineno"> 66</span> &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a0cf84d2efcb75476bf739a8313a69fd7">ATRRT::getFrontierNodeRatio</a>);</div>
<div class="line"><a id="l00067" name="l00067"></a><span class="lineno"> 67</span> Planner::declareParam<double>(<span class="stringliteral">"cost_threshold"</span>, <span class="keyword">this</span>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ad4987c7e6aa146b1f8f00e911efc9588">ATRRT::setCostThreshold</a>, &<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a001b5e82ceda23f33b1fe91806186c9c">ATRRT::getCostThreshold</a>);</div>
<div class="line"><a id="l00068" name="l00068"></a><span class="lineno"> 68</span>}</div>
</div>
<div class="line"><a id="l00069" name="l00069"></a><span class="lineno"> 69</span> </div>
<div class="line"><a id="l00070" name="l00070"></a><span class="lineno"> 70</span>ompl::geometric::ATRRT::~ATRRT()</div>
<div class="line"><a id="l00071" name="l00071"></a><span class="lineno"> 71</span>{</div>
<div class="line"><a id="l00072" name="l00072"></a><span class="lineno"> 72</span> freeMemory();</div>
<div class="line"><a id="l00073" name="l00073"></a><span class="lineno"> 73</span>}</div>
<div class="line"><a id="l00074" name="l00074"></a><span class="lineno"> 74</span> </div>
<div class="foldopen" id="foldopen00075" data-start="{" data-end="}">
<div class="line"><a id="l00075" name="l00075"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a8358273025a7acd5eb3a6e888344ebba"> 75</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a8358273025a7acd5eb3a6e888344ebba">ompl::geometric::ATRRT::clear</a>()</div>
<div class="line"><a id="l00076" name="l00076"></a><span class="lineno"> 76</span>{</div>
<div class="line"><a id="l00077" name="l00077"></a><span class="lineno"> 77</span> Planner::clear();</div>
<div class="line"><a id="l00078" name="l00078"></a><span class="lineno"> 78</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a55908a440d150d8fcf80d807186312dd">sampler_</a>.reset();</div>
<div class="line"><a id="l00079" name="l00079"></a><span class="lineno"> 79</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a3be7868273f5d5854961da6b604a3dda">freeMemory</a>();</div>
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"> 80</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>)</div>
<div class="line"><a id="l00081" name="l00081"></a><span class="lineno"> 81</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->clear();</div>
<div class="line"><a id="l00082" name="l00082"></a><span class="lineno"> 82</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1e6216de2a4230256b0396a30155b7d0">lastGoalMotion_</a> = <span class="keyword">nullptr</span>;</div>
<div class="line"><a id="l00083" name="l00083"></a><span class="lineno"> 83</span> </div>
<div class="line"><a id="l00084" name="l00084"></a><span class="lineno"> 84</span> <span class="comment">// Clear ATRRT specific variables ---------------------------------------------------------</span></div>
<div class="line"><a id="l00085" name="l00085"></a><span class="lineno"> 85</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">temp_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ac190ee401a05c61192b5f7ca7b04b4d9">initTemperature_</a>;</div>
<div class="line"><a id="l00086" name="l00086"></a><span class="lineno"> 86</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a2b641a42faab77cdf385ed1232fefa8e">nonfrontierCount_</a> = 1;</div>
<div class="line"><a id="l00087" name="l00087"></a><span class="lineno"> 87</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a88b0c1c157f86da8abcf0893df538886">frontierCount_</a> = 1; <span class="comment">// init to 1 to prevent division by zero error</span></div>
<div class="line"><a id="l00088" name="l00088"></a><span class="lineno"> 88</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>)</div>
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"> 89</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->infiniteCost();</div>
<div class="line"><a id="l00090" name="l00090"></a><span class="lineno"> 90</span>}</div>
</div>
<div class="line"><a id="l00091" name="l00091"></a><span class="lineno"> 91</span> </div>
<div class="foldopen" id="foldopen00092" data-start="{" data-end="}">
<div class="line"><a id="l00092" name="l00092"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#acca1522f2f3369560ace3d6761fa9752"> 92</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#acca1522f2f3369560ace3d6761fa9752">ompl::geometric::ATRRT::setup</a>()</div>
<div class="line"><a id="l00093" name="l00093"></a><span class="lineno"> 93</span>{</div>
<div class="line"><a id="l00094" name="l00094"></a><span class="lineno"> 94</span> Planner::setup();</div>
<div class="line"><a id="l00095" name="l00095"></a><span class="lineno"> 95</span> <a class="code hl_class" href="classompl_1_1tools_1_1SelfConfig.html">tools::SelfConfig</a> selfConfig(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>());</div>
<div class="line"><a id="l00096" name="l00096"></a><span class="lineno"> 96</span> </div>
<div class="line"><a id="l00097" name="l00097"></a><span class="lineno"> 97</span> <span class="keywordflow">if</span> (!<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a> || !<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->hasOptimizationObjective())</div>
<div class="line"><a id="l00098" name="l00098"></a><span class="lineno"> 98</span> {</div>
<div class="line"><a id="l00099" name="l00099"></a><span class="lineno"> 99</span> <a class="code hl_define" 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 id="l00100" name="l00100"></a><span class="lineno"> 100</span> <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a> = std::make_shared<base::MechanicalWorkOptimizationObjective>(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>);</div>
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span> }</div>
<div class="line"><a id="l00103" name="l00103"></a><span class="lineno"> 103</span> <span class="keywordflow">else</span></div>
<div class="line"><a id="l00104" name="l00104"></a><span class="lineno"> 104</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a> = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->getOptimizationObjective();</div>
<div class="line"><a id="l00105" name="l00105"></a><span class="lineno"> 105</span> </div>
<div class="line"><a id="l00106" name="l00106"></a><span class="lineno"> 106</span> <span class="comment">// Set maximum distance a new node can be from its nearest neighbor</span></div>
<div class="line"><a id="l00107" name="l00107"></a><span class="lineno"> 107</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a> < std::numeric_limits<double>::epsilon())</div>
<div class="line"><a id="l00108" name="l00108"></a><span class="lineno"> 108</span> {</div>
<div class="line"><a id="l00109" name="l00109"></a><span class="lineno"> 109</span> selfConfig.<a class="code hl_function" href="classompl_1_1tools_1_1SelfConfig.html#a65bff53ea4bc6f158342a856175ab9a6">configurePlannerRange</a>(<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a>);</div>
<div class="line"><a id="l00110" name="l00110"></a><span class="lineno"> 110</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a> *= <a class="code hl_variable" href="namespaceompl_1_1magic.html#a3c9c3d6c0ee87fea2dbc5fa7484d15fa">magic::COST_MAX_MOTION_LENGTH_AS_SPACE_EXTENT_FRACTION</a>;</div>
<div class="line"><a id="l00111" name="l00111"></a><span class="lineno"> 111</span> }</div>
<div class="line"><a id="l00112" name="l00112"></a><span class="lineno"> 112</span> </div>
<div class="line"><a id="l00113" name="l00113"></a><span class="lineno"> 113</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 id="l00114" name="l00114"></a><span class="lineno"> 114</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">frontierThreshold_</a> < std::numeric_limits<double>::epsilon())</div>
<div class="line"><a id="l00115" name="l00115"></a><span class="lineno"> 115</span> {</div>
<div class="line"><a id="l00116" name="l00116"></a><span class="lineno"> 116</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">frontierThreshold_</a> = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getMaximumExtent() * 0.01;</div>
<div class="line"><a id="l00117" name="l00117"></a><span class="lineno"> 117</span> <a class="code hl_define" href="group__logging.html#ga576d0bc79b521f19c5415f330e2b173d">OMPL_DEBUG</a>(<span class="stringliteral">"%s: Frontier threshold detected to be %lf"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str(), <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">frontierThreshold_</a>);</div>
<div class="line"><a id="l00118" name="l00118"></a><span class="lineno"> 118</span> }</div>
<div class="line"><a id="l00119" name="l00119"></a><span class="lineno"> 119</span> </div>
<div class="line"><a id="l00120" name="l00120"></a><span class="lineno"> 120</span> <span class="comment">// Create the nearest neighbor function the first time setup is run</span></div>
<div class="line"><a id="l00121" name="l00121"></a><span class="lineno"> 121</span> <span class="keywordflow">if</span> (!<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>)</div>
<div class="line"><a id="l00122" name="l00122"></a><span class="lineno"> 122</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>.reset(<a class="code hl_function" href="classompl_1_1tools_1_1SelfConfig.html#a23f1fef30af80542eeb4709465a06148">tools::SelfConfig::getDefaultNearestNeighbors<Motion *></a>(<span class="keyword">this</span>));</div>
<div class="line"><a id="l00123" name="l00123"></a><span class="lineno"> 123</span> </div>
<div class="line"><a id="l00124" name="l00124"></a><span class="lineno"> 124</span> <span class="comment">// Set the distance function</span></div>
<div class="line"><a id="l00125" name="l00125"></a><span class="lineno"> 125</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->setDistanceFunction([<span class="keyword">this</span>](<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *a, <span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *b) { <span class="keywordflow">return</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a15f3084ba584ab73339055c692dd2a44">distanceFunction</a>(a, b); });</div>
<div class="line"><a id="l00126" name="l00126"></a><span class="lineno"> 126</span> </div>
<div class="line"><a id="l00127" name="l00127"></a><span class="lineno"> 127</span> <span class="comment">// Setup ATRRT specific variables ---------------------------------------------------------</span></div>
<div class="line"><a id="l00128" name="l00128"></a><span class="lineno"> 128</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">temp_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ac190ee401a05c61192b5f7ca7b04b4d9">initTemperature_</a>;</div>
<div class="line"><a id="l00129" name="l00129"></a><span class="lineno"> 129</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->identityCost();</div>
<div class="line"><a id="l00130" name="l00130"></a><span class="lineno"> 130</span>}</div>
</div>
<div class="line"><a id="l00131" name="l00131"></a><span class="lineno"> 131</span> </div>
<div class="foldopen" id="foldopen00132" data-start="{" data-end="}">
<div class="line"><a id="l00132" name="l00132"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a3be7868273f5d5854961da6b604a3dda"> 132</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a3be7868273f5d5854961da6b604a3dda">ompl::geometric::ATRRT::freeMemory</a>()</div>
<div class="line"><a id="l00133" name="l00133"></a><span class="lineno"> 133</span>{</div>
<div class="line"><a id="l00134" name="l00134"></a><span class="lineno"> 134</span> <span class="comment">// Delete all motions, states and the nearest neighbors data structure</span></div>
<div class="line"><a id="l00135" name="l00135"></a><span class="lineno"> 135</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>)</div>
<div class="line"><a id="l00136" name="l00136"></a><span class="lineno"> 136</span> {</div>
<div class="line"><a id="l00137" name="l00137"></a><span class="lineno"> 137</span> std::vector<Motion *> motions;</div>
<div class="line"><a id="l00138" name="l00138"></a><span class="lineno"> 138</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->list(motions);</div>
<div class="line"><a id="l00139" name="l00139"></a><span class="lineno"> 139</span> <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a id="l00140" name="l00140"></a><span class="lineno"> 140</span> {</div>
<div class="line"><a id="l00141" name="l00141"></a><span class="lineno"> 141</span> <span class="keywordflow">if</span> (motion->state)</div>
<div class="line"><a id="l00142" name="l00142"></a><span class="lineno"> 142</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->freeState(motion->state);</div>
<div class="line"><a id="l00143" name="l00143"></a><span class="lineno"> 143</span> <span class="keyword">delete</span> motion;</div>
<div class="line"><a id="l00144" name="l00144"></a><span class="lineno"> 144</span> }</div>
<div class="line"><a id="l00145" name="l00145"></a><span class="lineno"> 145</span> }</div>
<div class="line"><a id="l00146" name="l00146"></a><span class="lineno"> 146</span>}</div>
</div>
<div class="line"><a id="l00147" name="l00147"></a><span class="lineno"> 147</span> </div>
<div class="foldopen" id="foldopen00148" data-start="{" data-end="}">
<div class="line"><a id="l00148" name="l00148"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a924f31761622fe7aafc313546c9542ee"> 148</a></span><a class="code hl_struct" href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a924f31761622fe7aafc313546c9542ee">ompl::geometric::ATRRT::solve</a>(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1PlannerTerminationCondition.html">base::PlannerTerminationCondition</a> &ptc)</div>
<div class="line"><a id="l00149" name="l00149"></a><span class="lineno"> 149</span>{</div>
<div class="line"><a id="l00150" name="l00150"></a><span class="lineno"> 150</span> <span class="comment">// Basic error checking</span></div>
<div class="line"><a id="l00151" name="l00151"></a><span class="lineno"> 151</span> <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#ab416900477cf4499139c01f35663dffb">checkValidity</a>();</div>
<div class="line"><a id="l00152" name="l00152"></a><span class="lineno"> 152</span> </div>
<div class="line"><a id="l00153" name="l00153"></a><span class="lineno"> 153</span> <span class="comment">// Goal information</span></div>
<div class="line"><a id="l00154" name="l00154"></a><span class="lineno"> 154</span> <a class="code hl_class" href="classompl_1_1base_1_1Goal.html">base::Goal</a> *goal = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->getGoal().get();</div>
<div class="line"><a id="l00155" name="l00155"></a><span class="lineno"> 155</span> <span class="keyword">auto</span> *goalRegion = <span class="keyword">dynamic_cast<</span><a class="code hl_class" href="classompl_1_1base_1_1GoalSampleableRegion.html">base::GoalSampleableRegion</a> *<span class="keyword">></span>(goal);</div>
<div class="line"><a id="l00156" name="l00156"></a><span class="lineno"> 156</span> </div>
<div class="line"><a id="l00157" name="l00157"></a><span class="lineno"> 157</span> <span class="keywordflow">if</span> (goalRegion == <span class="keyword">nullptr</span>)</div>
<div class="line"><a id="l00158" name="l00158"></a><span class="lineno"> 158</span> {</div>
<div class="line"><a id="l00159" name="l00159"></a><span class="lineno"> 159</span> <a class="code hl_define" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Unknown type of goal"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a id="l00160" name="l00160"></a><span class="lineno"> 160</span> <span class="keywordflow">return</span> <a class="code hl_enumvalue" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a47d769205044efa345184a640bd863ff">base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE</a>;</div>
<div class="line"><a id="l00161" name="l00161"></a><span class="lineno"> 161</span> }</div>
<div class="line"><a id="l00162" name="l00162"></a><span class="lineno"> 162</span> </div>
<div class="line"><a id="l00163" name="l00163"></a><span class="lineno"> 163</span> <span class="keywordflow">if</span> (!goalRegion->couldSample())</div>
<div class="line"><a id="l00164" name="l00164"></a><span class="lineno"> 164</span> {</div>
<div class="line"><a id="l00165" name="l00165"></a><span class="lineno"> 165</span> <a class="code hl_define" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: Insufficient states in sampleable goal region"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a id="l00166" name="l00166"></a><span class="lineno"> 166</span> <span class="keywordflow">return</span> <a class="code hl_enumvalue" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a2e2b2b7e02900c4417af0ecea272c637">base::PlannerStatus::INVALID_GOAL</a>;</div>
<div class="line"><a id="l00167" name="l00167"></a><span class="lineno"> 167</span> }</div>
<div class="line"><a id="l00168" name="l00168"></a><span class="lineno"> 168</span> </div>
<div class="line"><a id="l00169" name="l00169"></a><span class="lineno"> 169</span> <span class="comment">// Input States ---------------------------------------------------------------------------------</span></div>
<div class="line"><a id="l00170" name="l00170"></a><span class="lineno"> 170</span> </div>
<div class="line"><a id="l00171" name="l00171"></a><span class="lineno"> 171</span> <span class="comment">// Loop through valid input states and add to tree</span></div>
<div class="line"><a id="l00172" name="l00172"></a><span class="lineno"> 172</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *startMotion = <span class="keyword">nullptr</span>;</div>
<div class="line"><a id="l00173" name="l00173"></a><span class="lineno"> 173</span> <span class="keywordflow">while</span> (<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1State.html">base::State</a> *state = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a1c6ac45d44026aae6df87f3295d67436">pis_</a>.nextStart())</div>
<div class="line"><a id="l00174" name="l00174"></a><span class="lineno"> 174</span> {</div>
<div class="line"><a id="l00175" name="l00175"></a><span class="lineno"> 175</span> <span class="comment">// Allocate memory for a new start state motion based on the "space-information"-size</span></div>
<div class="line"><a id="l00176" name="l00176"></a><span class="lineno"> 176</span> <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a>(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>);</div>
<div class="line"><a id="l00177" name="l00177"></a><span class="lineno"> 177</span> </div>
<div class="line"><a id="l00178" name="l00178"></a><span class="lineno"> 178</span> <span class="comment">// Copy destination <= source</span></div>
<div class="line"><a id="l00179" name="l00179"></a><span class="lineno"> 179</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->copyState(motion->state, state);</div>
<div class="line"><a id="l00180" name="l00180"></a><span class="lineno"> 180</span> </div>
<div class="line"><a id="l00181" name="l00181"></a><span class="lineno"> 181</span> <span class="comment">// Set cost for this start state</span></div>
<div class="line"><a id="l00182" name="l00182"></a><span class="lineno"> 182</span> motion->cost = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->stateCost(motion->state);</div>
<div class="line"><a id="l00183" name="l00183"></a><span class="lineno"> 183</span> </div>
<div class="line"><a id="l00184" name="l00184"></a><span class="lineno"> 184</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->size() == 0) <span class="comment">// do not overwrite best/worst from previous call to solve</span></div>
<div class="line"><a id="l00185" name="l00185"></a><span class="lineno"> 185</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a> = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a> = motion->cost;</div>
<div class="line"><a id="l00186" name="l00186"></a><span class="lineno"> 186</span> </div>
<div class="line"><a id="l00187" name="l00187"></a><span class="lineno"> 187</span> <span class="comment">// Add start motion to the tree</span></div>
<div class="line"><a id="l00188" name="l00188"></a><span class="lineno"> 188</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->add(motion);</div>
<div class="line"><a id="l00189" name="l00189"></a><span class="lineno"> 189</span> </div>
<div class="line"><a id="l00190" name="l00190"></a><span class="lineno"> 190</span> <span class="comment">// Keep track of the start motion</span></div>
<div class="line"><a id="l00191" name="l00191"></a><span class="lineno"> 191</span> <span class="keywordflow">if</span> (startMotion == <span class="keyword">nullptr</span>)</div>
<div class="line"><a id="l00192" name="l00192"></a><span class="lineno"> 192</span> startMotion = motion;</div>
<div class="line"><a id="l00193" name="l00193"></a><span class="lineno"> 193</span> }</div>
<div class="line"><a id="l00194" name="l00194"></a><span class="lineno"> 194</span> </div>
<div class="line"><a id="l00195" name="l00195"></a><span class="lineno"> 195</span> <span class="comment">// Check that input states exist</span></div>
<div class="line"><a id="l00196" name="l00196"></a><span class="lineno"> 196</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->size() == 0)</div>
<div class="line"><a id="l00197" name="l00197"></a><span class="lineno"> 197</span> {</div>
<div class="line"><a id="l00198" name="l00198"></a><span class="lineno"> 198</span> <a class="code hl_define" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"%s: There are no valid initial states!"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str());</div>
<div class="line"><a id="l00199" name="l00199"></a><span class="lineno"> 199</span> <span class="keywordflow">return</span> <a class="code hl_enumvalue" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4a1f20d012b563fc223902e24a8bcd7547">base::PlannerStatus::INVALID_START</a>;</div>
<div class="line"><a id="l00200" name="l00200"></a><span class="lineno"> 200</span> }</div>
<div class="line"><a id="l00201" name="l00201"></a><span class="lineno"> 201</span> </div>
<div class="line"><a id="l00202" name="l00202"></a><span class="lineno"> 202</span> <span class="comment">// Create state sampler if this is ATRRT's first run</span></div>
<div class="line"><a id="l00203" name="l00203"></a><span class="lineno"> 203</span> <span class="keywordflow">if</span> (!<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a55908a440d150d8fcf80d807186312dd">sampler_</a>)</div>
<div class="line"><a id="l00204" name="l00204"></a><span class="lineno"> 204</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a55908a440d150d8fcf80d807186312dd">sampler_</a> = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->allocStateSampler();</div>
<div class="line"><a id="l00205" name="l00205"></a><span class="lineno"> 205</span> </div>
<div class="line"><a id="l00206" name="l00206"></a><span class="lineno"> 206</span> <span class="comment">// Debug</span></div>
<div class="line"><a id="l00207" name="l00207"></a><span class="lineno"> 207</span> <a class="code hl_define" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Starting planning with %u states already in datastructure"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str(),</div>
<div class="line"><a id="l00208" name="l00208"></a><span class="lineno"> 208</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->size());</div>
<div class="line"><a id="l00209" name="l00209"></a><span class="lineno"> 209</span> </div>
<div class="line"><a id="l00210" name="l00210"></a><span class="lineno"> 210</span> <span class="comment">// Solver variables ------------------------------------------------------------------------------------</span></div>
<div class="line"><a id="l00211" name="l00211"></a><span class="lineno"> 211</span> </div>
<div class="line"><a id="l00212" name="l00212"></a><span class="lineno"> 212</span> <span class="comment">// the final solution</span></div>
<div class="line"><a id="l00213" name="l00213"></a><span class="lineno"> 213</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *solution = <span class="keyword">nullptr</span>;</div>
<div class="line"><a id="l00214" name="l00214"></a><span class="lineno"> 214</span> <span class="comment">// the approximate solution, returned if no final solution found</span></div>
<div class="line"><a id="l00215" name="l00215"></a><span class="lineno"> 215</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *approxSolution = <span class="keyword">nullptr</span>;</div>
<div class="line"><a id="l00216" name="l00216"></a><span class="lineno"> 216</span> <span class="comment">// track the distance from goal to closest solution yet found</span></div>
<div class="line"><a id="l00217" name="l00217"></a><span class="lineno"> 217</span> <span class="keywordtype">double</span> approxDifference = std::numeric_limits<double>::infinity();</div>
<div class="line"><a id="l00218" name="l00218"></a><span class="lineno"> 218</span> <span class="comment">// UsefulCycles constant</span></div>
<div class="line"><a id="l00219" name="l00219"></a><span class="lineno"> 219</span> <span class="keywordtype">double</span> volumeFreeSpace = 0.9 * <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getMaximumExtent();</div>
<div class="line"><a id="l00220" name="l00220"></a><span class="lineno"> 220</span> <span class="keywordtype">double</span> volumeUnitBall2D = M_PI;</div>
<div class="line"><a id="l00221" name="l00221"></a><span class="lineno"> 221</span> <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> d = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateDimension();</div>
<div class="line"><a id="l00222" name="l00222"></a><span class="lineno"> 222</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#af59e77284d1fa9c923ceaf29a6eb40b5">gamma_</a> = 2.5 * 2 * std::pow((1.0 + 1.0 / d), 1.0 / d) * std::pow(volumeFreeSpace / volumeUnitBall2D, 1.0 / d);</div>
<div class="line"><a id="l00223" name="l00223"></a><span class="lineno"> 223</span> </div>
<div class="line"><a id="l00224" name="l00224"></a><span class="lineno"> 224</span> <span class="comment">// distance between states - the initial state and the interpolated state (may be the same)</span></div>
<div class="line"><a id="l00225" name="l00225"></a><span class="lineno"> 225</span> <span class="keywordtype">double</span> randMotionDistance;</div>
<div class="line"><a id="l00226" name="l00226"></a><span class="lineno"> 226</span> </div>
<div class="line"><a id="l00227" name="l00227"></a><span class="lineno"> 227</span> <span class="comment">// Create random motion and a pointer (for optimization) to its state</span></div>
<div class="line"><a id="l00228" name="l00228"></a><span class="lineno"> 228</span> <span class="keyword">auto</span> *randMotion = <span class="keyword">new</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a>(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>);</div>
<div class="line"><a id="l00229" name="l00229"></a><span class="lineno"> 229</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *nearMotion;</div>
<div class="line"><a id="l00230" name="l00230"></a><span class="lineno"> 230</span> </div>
<div class="line"><a id="l00231" name="l00231"></a><span class="lineno"> 231</span> <span class="comment">// STATES</span></div>
<div class="line"><a id="l00232" name="l00232"></a><span class="lineno"> 232</span> <span class="comment">// The random state</span></div>
<div class="line"><a id="l00233" name="l00233"></a><span class="lineno"> 233</span> <a class="code hl_class" href="classompl_1_1base_1_1State.html">base::State</a> *randState = randMotion->state;</div>
<div class="line"><a id="l00234" name="l00234"></a><span class="lineno"> 234</span> <span class="comment">// The new state that is generated between states *to* and *from*</span></div>
<div class="line"><a id="l00235" name="l00235"></a><span class="lineno"> 235</span> <a class="code hl_class" href="classompl_1_1base_1_1State.html">base::State</a> *interpolatedState = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->allocState();</div>
<div class="line"><a id="l00236" name="l00236"></a><span class="lineno"> 236</span> <span class="comment">// The chosen state btw rand_state and interpolated_state</span></div>
<div class="line"><a id="l00237" name="l00237"></a><span class="lineno"> 237</span> <a class="code hl_class" href="classompl_1_1base_1_1State.html">base::State</a> *newState;</div>
<div class="line"><a id="l00238" name="l00238"></a><span class="lineno"> 238</span> </div>
<div class="line"><a id="l00239" name="l00239"></a><span class="lineno"> 239</span> <span class="comment">// Begin sampling --------------------------------------------------------------------------------------</span></div>
<div class="line"><a id="l00240" name="l00240"></a><span class="lineno"> 240</span> <span class="keywordflow">while</span> (!ptc)</div>
<div class="line"><a id="l00241" name="l00241"></a><span class="lineno"> 241</span> {</div>
<div class="line"><a id="l00242" name="l00242"></a><span class="lineno"> 242</span> <span class="comment">// I.</span></div>
<div class="line"><a id="l00243" name="l00243"></a><span class="lineno"> 243</span> </div>
<div class="line"><a id="l00244" name="l00244"></a><span class="lineno"> 244</span> <span class="comment">// Sample random state (with goal biasing)</span></div>
<div class="line"><a id="l00245" name="l00245"></a><span class="lineno"> 245</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ab648a6f0de2d4f8f2425f6ae4facff86">rng_</a>.uniform01() < <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a2653af9be56df732b1f025beee47186a">goalBias_</a> && goalRegion->canSample())</div>
<div class="line"><a id="l00246" name="l00246"></a><span class="lineno"> 246</span> {</div>
<div class="line"><a id="l00247" name="l00247"></a><span class="lineno"> 247</span> <span class="comment">// Bias sample towards goal</span></div>
<div class="line"><a id="l00248" name="l00248"></a><span class="lineno"> 248</span> goalRegion->sampleGoal(randState);</div>
<div class="line"><a id="l00249" name="l00249"></a><span class="lineno"> 249</span> }</div>
<div class="line"><a id="l00250" name="l00250"></a><span class="lineno"> 250</span> <span class="keywordflow">else</span></div>
<div class="line"><a id="l00251" name="l00251"></a><span class="lineno"> 251</span> {</div>
<div class="line"><a id="l00252" name="l00252"></a><span class="lineno"> 252</span> <span class="comment">// Uniformly Sample</span></div>
<div class="line"><a id="l00253" name="l00253"></a><span class="lineno"> 253</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a55908a440d150d8fcf80d807186312dd">sampler_</a>->sampleUniform(randState);</div>
<div class="line"><a id="l00254" name="l00254"></a><span class="lineno"> 254</span> }</div>
<div class="line"><a id="l00255" name="l00255"></a><span class="lineno"> 255</span> </div>
<div class="line"><a id="l00256" name="l00256"></a><span class="lineno"> 256</span> <span class="comment">// II.</span></div>
<div class="line"><a id="l00257" name="l00257"></a><span class="lineno"> 257</span> </div>
<div class="line"><a id="l00258" name="l00258"></a><span class="lineno"> 258</span> <span class="comment">// Find closest state in the tree</span></div>
<div class="line"><a id="l00259" name="l00259"></a><span class="lineno"> 259</span> nearMotion = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->nearest(randMotion);</div>
<div class="line"><a id="l00260" name="l00260"></a><span class="lineno"> 260</span> </div>
<div class="line"><a id="l00261" name="l00261"></a><span class="lineno"> 261</span> <span class="comment">// III.</span></div>
<div class="line"><a id="l00262" name="l00262"></a><span class="lineno"> 262</span> </div>
<div class="line"><a id="l00263" name="l00263"></a><span class="lineno"> 263</span> <span class="comment">// Distance from near state q_n to a random state</span></div>
<div class="line"><a id="l00264" name="l00264"></a><span class="lineno"> 264</span> randMotionDistance = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->distance(nearMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, randState);</div>
<div class="line"><a id="l00265" name="l00265"></a><span class="lineno"> 265</span> </div>
<div class="line"><a id="l00266" name="l00266"></a><span class="lineno"> 266</span> <span class="comment">// Check if the rand_state is too far away</span></div>
<div class="line"><a id="l00267" name="l00267"></a><span class="lineno"> 267</span> <span class="keywordflow">if</span> (randMotionDistance > <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a>)</div>
<div class="line"><a id="l00268" name="l00268"></a><span class="lineno"> 268</span> {</div>
<div class="line"><a id="l00269" name="l00269"></a><span class="lineno"> 269</span> <span class="comment">// Computes the state that lies at time t in [0, 1] on the segment that connects *from* state to *to* state.</span></div>
<div class="line"><a id="l00270" name="l00270"></a><span class="lineno"> 270</span> <span class="comment">// The memory location of *state* is not required to be different from the memory of either *from* or *to*.</span></div>
<div class="line"><a id="l00271" name="l00271"></a><span class="lineno"> 271</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->getStateSpace()->interpolate(nearMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, randState, <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a> / randMotionDistance,</div>
<div class="line"><a id="l00272" name="l00272"></a><span class="lineno"> 272</span> interpolatedState);</div>
<div class="line"><a id="l00273" name="l00273"></a><span class="lineno"> 273</span> </div>
<div class="line"><a id="l00274" name="l00274"></a><span class="lineno"> 274</span> <span class="comment">// Update the distance between near and new with the interpolated_state</span></div>
<div class="line"><a id="l00275" name="l00275"></a><span class="lineno"> 275</span> randMotionDistance = <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->distance(nearMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, interpolatedState);</div>
<div class="line"><a id="l00276" name="l00276"></a><span class="lineno"> 276</span> </div>
<div class="line"><a id="l00277" name="l00277"></a><span class="lineno"> 277</span> <span class="comment">// Use the interpolated state as the new state</span></div>
<div class="line"><a id="l00278" name="l00278"></a><span class="lineno"> 278</span> newState = interpolatedState;</div>
<div class="line"><a id="l00279" name="l00279"></a><span class="lineno"> 279</span> }</div>
<div class="line"><a id="l00280" name="l00280"></a><span class="lineno"> 280</span> <span class="keywordflow">else</span> <span class="comment">// Random state is close enough</span></div>
<div class="line"><a id="l00281" name="l00281"></a><span class="lineno"> 281</span> newState = randState;</div>
<div class="line"><a id="l00282" name="l00282"></a><span class="lineno"> 282</span> </div>
<div class="line"><a id="l00283" name="l00283"></a><span class="lineno"> 283</span> <span class="comment">// IV.</span></div>
<div class="line"><a id="l00284" name="l00284"></a><span class="lineno"> 284</span> <span class="comment">// this stage integrates collision detections in the presence of obstacles and checks for collisions</span></div>
<div class="line"><a id="l00285" name="l00285"></a><span class="lineno"> 285</span> <span class="keywordflow">if</span> (!<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->checkMotion(nearMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, newState))</div>
<div class="line"><a id="l00286" name="l00286"></a><span class="lineno"> 286</span> <span class="keywordflow">continue</span>; <span class="comment">// try a new sample</span></div>
<div class="line"><a id="l00287" name="l00287"></a><span class="lineno"> 287</span> </div>
<div class="line"><a id="l00288" name="l00288"></a><span class="lineno"> 288</span> <span class="comment">// Minimum Expansion Control</span></div>
<div class="line"><a id="l00289" name="l00289"></a><span class="lineno"> 289</span> <span class="comment">// A possible side effect may appear when the tree expansion toward unexplored regions remains slow, and the</span></div>
<div class="line"><a id="l00290" name="l00290"></a><span class="lineno"> 290</span> <span class="comment">// new nodes contribute only to refine already explored regions.</span></div>
<div class="line"><a id="l00291" name="l00291"></a><span class="lineno"> 291</span> <span class="keywordflow">if</span> (solution == <span class="keyword">nullptr</span> && !<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a4052b590b03f222f9e9b71ef5a75cba9">minExpansionControl</a>(randMotionDistance))</div>
<div class="line"><a id="l00292" name="l00292"></a><span class="lineno"> 292</span> <span class="keywordflow">continue</span>; <span class="comment">// try a new sample</span></div>
<div class="line"><a id="l00293" name="l00293"></a><span class="lineno"> 293</span> </div>
<div class="line"><a id="l00294" name="l00294"></a><span class="lineno"> 294</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> childCost = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->stateCost(newState);</div>
<div class="line"><a id="l00295" name="l00295"></a><span class="lineno"> 295</span> </div>
<div class="line"><a id="l00296" name="l00296"></a><span class="lineno"> 296</span> <span class="comment">// Only add this motion to the tree if the transition test accepts it</span></div>
<div class="line"><a id="l00297" name="l00297"></a><span class="lineno"> 297</span> <span class="keywordflow">if</span> (!<a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a3736b8795b366bd8254bf25a26b879e5">transitionTest</a>(<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->motionCost(nearMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, newState)))</div>
<div class="line"><a id="l00298" name="l00298"></a><span class="lineno"> 298</span> <span class="keywordflow">continue</span>; <span class="comment">// try a new sample</span></div>
<div class="line"><a id="l00299" name="l00299"></a><span class="lineno"> 299</span> </div>
<div class="line"><a id="l00300" name="l00300"></a><span class="lineno"> 300</span> <span class="comment">// V.</span></div>
<div class="line"><a id="l00301" name="l00301"></a><span class="lineno"> 301</span> </div>
<div class="line"><a id="l00302" name="l00302"></a><span class="lineno"> 302</span> <span class="comment">// Create a motion</span></div>
<div class="line"><a id="l00303" name="l00303"></a><span class="lineno"> 303</span> <span class="keyword">auto</span> *motion = <span class="keyword">new</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a>(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>);</div>
<div class="line"><a id="l00304" name="l00304"></a><span class="lineno"> 304</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->copyState(motion->state, newState);</div>
<div class="line"><a id="l00305" name="l00305"></a><span class="lineno"> 305</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ae8d7a530bfa540df794e6dbdffa9ab56">addEdge</a>(motion, nearMotion); <span class="comment">// link q_new to q_near as an edge</span></div>
<div class="line"><a id="l00306" name="l00306"></a><span class="lineno"> 306</span> motion->cost = childCost;</div>
<div class="line"><a id="l00307" name="l00307"></a><span class="lineno"> 307</span> </div>
<div class="line"><a id="l00308" name="l00308"></a><span class="lineno"> 308</span> <span class="comment">// Add motion to data structure</span></div>
<div class="line"><a id="l00309" name="l00309"></a><span class="lineno"> 309</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->add(motion);</div>
<div class="line"><a id="l00310" name="l00310"></a><span class="lineno"> 310</span> </div>
<div class="line"><a id="l00311" name="l00311"></a><span class="lineno"> 311</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->isCostBetterThan(motion->cost, <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a>)) <span class="comment">// motion->cost is better than the existing best</span></div>
<div class="line"><a id="l00312" name="l00312"></a><span class="lineno"> 312</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a> = motion->cost;</div>
<div class="line"><a id="l00313" name="l00313"></a><span class="lineno"> 313</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->isCostBetterThan(<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a>, motion->cost)) <span class="comment">// motion->cost is worse than the existing worst</span></div>
<div class="line"><a id="l00314" name="l00314"></a><span class="lineno"> 314</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a> = motion->cost;</div>
<div class="line"><a id="l00315" name="l00315"></a><span class="lineno"> 315</span> </div>
<div class="line"><a id="l00316" name="l00316"></a><span class="lineno"> 316</span> <span class="comment">// VI.</span></div>
<div class="line"><a id="l00317" name="l00317"></a><span class="lineno"> 317</span> </div>
<div class="line"><a id="l00318" name="l00318"></a><span class="lineno"> 318</span> <span class="comment">// Check if this motion is the goal</span></div>
<div class="line"><a id="l00319" name="l00319"></a><span class="lineno"> 319</span> <span class="keywordtype">double</span> distToGoal = 0.0;</div>
<div class="line"><a id="l00320" name="l00320"></a><span class="lineno"> 320</span> <span class="keywordtype">bool</span> isSatisfied = goal-><a class="code hl_function" href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec">isSatisfied</a>(motion->state, &distToGoal);</div>
<div class="line"><a id="l00321" name="l00321"></a><span class="lineno"> 321</span> <span class="keywordflow">if</span> (isSatisfied)</div>
<div class="line"><a id="l00322" name="l00322"></a><span class="lineno"> 322</span> {</div>
<div class="line"><a id="l00323" name="l00323"></a><span class="lineno"> 323</span> approxDifference = distToGoal; <span class="comment">// the tolerated error distance btw state and goal</span></div>
<div class="line"><a id="l00324" name="l00324"></a><span class="lineno"> 324</span> solution = motion; <span class="comment">// set the final solution</span></div>
<div class="line"><a id="l00325" name="l00325"></a><span class="lineno"> 325</span> }</div>
<div class="line"><a id="l00326" name="l00326"></a><span class="lineno"> 326</span> </div>
<div class="line"><a id="l00327" name="l00327"></a><span class="lineno"> 327</span> <span class="comment">// Is this the closest solution we've found so far</span></div>
<div class="line"><a id="l00328" name="l00328"></a><span class="lineno"> 328</span> <span class="keywordflow">if</span> (distToGoal < approxDifference)</div>
<div class="line"><a id="l00329" name="l00329"></a><span class="lineno"> 329</span> {</div>
<div class="line"><a id="l00330" name="l00330"></a><span class="lineno"> 330</span> approxDifference = distToGoal;</div>
<div class="line"><a id="l00331" name="l00331"></a><span class="lineno"> 331</span> approxSolution = motion;</div>
<div class="line"><a id="l00332" name="l00332"></a><span class="lineno"> 332</span> }</div>
<div class="line"><a id="l00333" name="l00333"></a><span class="lineno"> 333</span> </div>
<div class="line"><a id="l00334" name="l00334"></a><span class="lineno"> 334</span> <span class="comment">// VII. Add cycles to the graph if an initial solution exists</span></div>
<div class="line"><a id="l00335" name="l00335"></a><span class="lineno"> 335</span> <span class="keywordflow">if</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a id="l00336" name="l00336"></a><span class="lineno"> 336</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ae38e1715b076afe492b47615a9e05d5c">addUsefulCycles</a>(motion, nearMotion);</div>
<div class="line"><a id="l00337" name="l00337"></a><span class="lineno"> 337</span> </div>
<div class="line"><a id="l00338" name="l00338"></a><span class="lineno"> 338</span> } <span class="comment">// end of solver sampling loop</span></div>
<div class="line"><a id="l00339" name="l00339"></a><span class="lineno"> 339</span> </div>
<div class="line"><a id="l00340" name="l00340"></a><span class="lineno"> 340</span> <span class="comment">// Finish solution processing --------------------------------------------------------------------</span></div>
<div class="line"><a id="l00341" name="l00341"></a><span class="lineno"> 341</span> </div>
<div class="line"><a id="l00342" name="l00342"></a><span class="lineno"> 342</span> <span class="keywordtype">bool</span> solved = <span class="keyword">false</span>;</div>
<div class="line"><a id="l00343" name="l00343"></a><span class="lineno"> 343</span> <span class="keywordtype">bool</span> approximate = <span class="keyword">false</span>;</div>
<div class="line"><a id="l00344" name="l00344"></a><span class="lineno"> 344</span> </div>
<div class="line"><a id="l00345" name="l00345"></a><span class="lineno"> 345</span> <span class="comment">// Substitute an empty solution with the best approximation</span></div>
<div class="line"><a id="l00346" name="l00346"></a><span class="lineno"> 346</span> <span class="keywordflow">if</span> (solution == <span class="keyword">nullptr</span>)</div>
<div class="line"><a id="l00347" name="l00347"></a><span class="lineno"> 347</span> {</div>
<div class="line"><a id="l00348" name="l00348"></a><span class="lineno"> 348</span> solution = approxSolution;</div>
<div class="line"><a id="l00349" name="l00349"></a><span class="lineno"> 349</span> approximate = <span class="keyword">true</span>;</div>
<div class="line"><a id="l00350" name="l00350"></a><span class="lineno"> 350</span> }</div>
<div class="line"><a id="l00351" name="l00351"></a><span class="lineno"> 351</span> </div>
<div class="line"><a id="l00352" name="l00352"></a><span class="lineno"> 352</span> <span class="comment">// Generate solution path for real/approx solution</span></div>
<div class="line"><a id="l00353" name="l00353"></a><span class="lineno"> 353</span> <span class="keywordflow">if</span> (solution != <span class="keyword">nullptr</span>)</div>
<div class="line"><a id="l00354" name="l00354"></a><span class="lineno"> 354</span> {</div>
<div class="line"><a id="l00355" name="l00355"></a><span class="lineno"> 355</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1e6216de2a4230256b0396a30155b7d0">lastGoalMotion_</a> = solution;</div>
<div class="line"><a id="l00356" name="l00356"></a><span class="lineno"> 356</span> </div>
<div class="line"><a id="l00357" name="l00357"></a><span class="lineno"> 357</span> std::vector<Motion *> mpath = <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ad0dd091ed089ab90023125579582bc72">computeDijkstraLowestCostPath</a>(startMotion, solution);</div>
<div class="line"><a id="l00358" name="l00358"></a><span class="lineno"> 358</span> </div>
<div class="line"><a id="l00359" name="l00359"></a><span class="lineno"> 359</span> <span class="comment">// set the solution path</span></div>
<div class="line"><a id="l00360" name="l00360"></a><span class="lineno"> 360</span> <span class="keyword">auto</span> path(std::make_shared<PathGeometric>(<a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>));</div>
<div class="line"><a id="l00361" name="l00361"></a><span class="lineno"> 361</span> <span class="keywordflow">for</span> (<span class="keywordtype">int</span> i = mpath.size() - 1; i >= 0; --i)</div>
<div class="line"><a id="l00362" name="l00362"></a><span class="lineno"> 362</span> path->append(mpath[i]->state);</div>
<div class="line"><a id="l00363" name="l00363"></a><span class="lineno"> 363</span> </div>
<div class="line"><a id="l00364" name="l00364"></a><span class="lineno"> 364</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">pdef_</a>->addSolutionPath(path, approximate, approxDifference, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>());</div>
<div class="line"><a id="l00365" name="l00365"></a><span class="lineno"> 365</span> solved = <span class="keyword">true</span>;</div>
<div class="line"><a id="l00366" name="l00366"></a><span class="lineno"> 366</span> }</div>
<div class="line"><a id="l00367" name="l00367"></a><span class="lineno"> 367</span> </div>
<div class="line"><a id="l00368" name="l00368"></a><span class="lineno"> 368</span> <span class="comment">// Clean up ---------------------------------------------------------------------------------------</span></div>
<div class="line"><a id="l00369" name="l00369"></a><span class="lineno"> 369</span> </div>
<div class="line"><a id="l00370" name="l00370"></a><span class="lineno"> 370</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->freeState(interpolatedState);</div>
<div class="line"><a id="l00371" name="l00371"></a><span class="lineno"> 371</span> <span class="keywordflow">if</span> (randMotion->state)</div>
<div class="line"><a id="l00372" name="l00372"></a><span class="lineno"> 372</span> <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->freeState(randMotion->state);</div>
<div class="line"><a id="l00373" name="l00373"></a><span class="lineno"> 373</span> <span class="keyword">delete</span> randMotion;</div>
<div class="line"><a id="l00374" name="l00374"></a><span class="lineno"> 374</span> </div>
<div class="line"><a id="l00375" name="l00375"></a><span class="lineno"> 375</span> <a class="code hl_define" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"%s: Created %u states"</span>, <a class="code hl_function" href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">getName</a>().c_str(), <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->size());</div>
<div class="line"><a id="l00376" name="l00376"></a><span class="lineno"> 376</span> </div>
<div class="line"><a id="l00377" name="l00377"></a><span class="lineno"> 377</span> <span class="keywordflow">return</span> {solved, approximate};</div>
<div class="line"><a id="l00378" name="l00378"></a><span class="lineno"> 378</span>}</div>
</div>
<div class="line"><a id="l00379" name="l00379"></a><span class="lineno"> 379</span> </div>
<div class="foldopen" id="foldopen00380" data-start="{" data-end="}">
<div class="line"><a id="l00380" name="l00380"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a79e6f480ac6c6a53b7c8ad05082bde53"> 380</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a79e6f480ac6c6a53b7c8ad05082bde53">ompl::geometric::ATRRT::getPlannerData</a>(<a class="code hl_class" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> &data)<span class="keyword"> const</span></div>
<div class="line"><a id="l00381" name="l00381"></a><span class="lineno"> 381</span><span class="keyword"></span>{</div>
<div class="line"><a id="l00382" name="l00382"></a><span class="lineno"> 382</span> Planner::getPlannerData(data);</div>
<div class="line"><a id="l00383" name="l00383"></a><span class="lineno"> 383</span> </div>
<div class="line"><a id="l00384" name="l00384"></a><span class="lineno"> 384</span> std::vector<Motion *> motions;</div>
<div class="line"><a id="l00385" name="l00385"></a><span class="lineno"> 385</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>)</div>
<div class="line"><a id="l00386" name="l00386"></a><span class="lineno"> 386</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->list(motions);</div>
<div class="line"><a id="l00387" name="l00387"></a><span class="lineno"> 387</span> </div>
<div class="line"><a id="l00388" name="l00388"></a><span class="lineno"> 388</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1e6216de2a4230256b0396a30155b7d0">lastGoalMotion_</a>)</div>
<div class="line"><a id="l00389" name="l00389"></a><span class="lineno"> 389</span> data.<a class="code hl_function" href="classompl_1_1base_1_1PlannerData.html#a3604cb85b0402b09b319c5f1df02b12e">addGoalVertex</a>(<a class="code hl_class" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1e6216de2a4230256b0396a30155b7d0">lastGoalMotion_</a>->state));</div>
<div class="line"><a id="l00390" name="l00390"></a><span class="lineno"> 390</span> </div>
<div class="line"><a id="l00391" name="l00391"></a><span class="lineno"> 391</span> <span class="keywordflow">for</span> (<span class="keyword">auto</span> &motion : motions)</div>
<div class="line"><a id="l00392" name="l00392"></a><span class="lineno"> 392</span> {</div>
<div class="line"><a id="l00393" name="l00393"></a><span class="lineno"> 393</span> <span class="keywordflow">if</span> (motion->neighbors.empty())</div>
<div class="line"><a id="l00394" name="l00394"></a><span class="lineno"> 394</span> data.<a class="code hl_function" href="classompl_1_1base_1_1PlannerData.html#a2eea84456784452486aa0065af391f47">addStartVertex</a>(<a class="code hl_class" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state));</div>
<div class="line"><a id="l00395" name="l00395"></a><span class="lineno"> 395</span> <span class="keywordflow">else</span></div>
<div class="line"><a id="l00396" name="l00396"></a><span class="lineno"> 396</span> <span class="keywordflow">for</span> (<span class="keyword">auto</span> &neighbor : motion->neighbors)</div>
<div class="line"><a id="l00397" name="l00397"></a><span class="lineno"> 397</span> data.<a class="code hl_function" href="classompl_1_1base_1_1PlannerData.html#ac09c21494a8c7db500ef1a66bbbb1aa7">addEdge</a>(<a class="code hl_class" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(neighbor->state), <a class="code hl_class" href="classompl_1_1base_1_1PlannerDataVertex.html">base::PlannerDataVertex</a>(motion->state));</div>
<div class="line"><a id="l00398" name="l00398"></a><span class="lineno"> 398</span> }</div>
<div class="line"><a id="l00399" name="l00399"></a><span class="lineno"> 399</span>}</div>
</div>
<div class="line"><a id="l00400" name="l00400"></a><span class="lineno"> 400</span> </div>
<div class="foldopen" id="foldopen00401" data-start="{" data-end="}">
<div class="line"><a id="l00401" name="l00401"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a3736b8795b366bd8254bf25a26b879e5"> 401</a></span><span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a3736b8795b366bd8254bf25a26b879e5">ompl::geometric::ATRRT::transitionTest</a>(<span class="keyword">const</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> &motionCost)</div>
<div class="line"><a id="l00402" name="l00402"></a><span class="lineno"> 402</span>{</div>
<div class="line"><a id="l00403" name="l00403"></a><span class="lineno"> 403</span> <span class="comment">// Disallow any cost that is not better than the cost threshold</span></div>
<div class="line"><a id="l00404" name="l00404"></a><span class="lineno"> 404</span> <span class="keywordflow">if</span> (!<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->isCostBetterThan(motionCost, <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a838a67a4af1929606ff32221de7f9fe1">costThreshold_</a>))</div>
<div class="line"><a id="l00405" name="l00405"></a><span class="lineno"> 405</span> <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a id="l00406" name="l00406"></a><span class="lineno"> 406</span> </div>
<div class="line"><a id="l00407" name="l00407"></a><span class="lineno"> 407</span> <span class="comment">// Always accept if the cost is near or below zero</span></div>
<div class="line"><a id="l00408" name="l00408"></a><span class="lineno"> 408</span> <span class="keywordflow">if</span> (motionCost.<a class="code hl_function" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>() < 1e-4)</div>
<div class="line"><a id="l00409" name="l00409"></a><span class="lineno"> 409</span> <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a id="l00410" name="l00410"></a><span class="lineno"> 410</span> </div>
<div class="line"><a id="l00411" name="l00411"></a><span class="lineno"> 411</span> <span class="keywordtype">double</span> dCost = motionCost.<a class="code hl_function" href="classompl_1_1base_1_1Cost.html#a3cd5c47c10a591badea945b4fc84014c">value</a>();</div>
<div class="line"><a id="l00412" name="l00412"></a><span class="lineno"> 412</span> <span class="keywordtype">double</span> transitionProbability = exp(-dCost / <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">temp_</a>);</div>
<div class="line"><a id="l00413" name="l00413"></a><span class="lineno"> 413</span> <span class="keywordflow">if</span> (transitionProbability > 0.5)</div>
<div class="line"><a id="l00414" name="l00414"></a><span class="lineno"> 414</span> {</div>
<div class="line"><a id="l00415" name="l00415"></a><span class="lineno"> 415</span> <span class="keywordtype">double</span> costRange = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">worstCost_</a>.value() - <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">bestCost_</a>.value();</div>
<div class="line"><a id="l00416" name="l00416"></a><span class="lineno"> 416</span> <span class="keywordflow">if</span> (fabs(costRange) > 1e-4) <span class="comment">// Do not divide by zero</span></div>
<div class="line"><a id="l00417" name="l00417"></a><span class="lineno"> 417</span> <span class="comment">// Successful transition test. Decrease the temperature slightly</span></div>
<div class="line"><a id="l00418" name="l00418"></a><span class="lineno"> 418</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">temp_</a> /= exp(dCost / (0.1 * costRange));</div>
<div class="line"><a id="l00419" name="l00419"></a><span class="lineno"> 419</span> </div>
<div class="line"><a id="l00420" name="l00420"></a><span class="lineno"> 420</span> <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a id="l00421" name="l00421"></a><span class="lineno"> 421</span> }</div>
<div class="line"><a id="l00422" name="l00422"></a><span class="lineno"> 422</span> </div>
<div class="line"><a id="l00423" name="l00423"></a><span class="lineno"> 423</span> <span class="comment">// The transition failed. Increase the temperature (slightly)</span></div>
<div class="line"><a id="l00424" name="l00424"></a><span class="lineno"> 424</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">temp_</a> *= <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ac8b09796cfcfa8f78b2df724e55babe1">tempChangeFactor_</a>;</div>
<div class="line"><a id="l00425" name="l00425"></a><span class="lineno"> 425</span> <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a id="l00426" name="l00426"></a><span class="lineno"> 426</span>}</div>
</div>
<div class="line"><a id="l00427" name="l00427"></a><span class="lineno"> 427</span> </div>
<div class="foldopen" id="foldopen00428" data-start="{" data-end="}">
<div class="line"><a id="l00428" name="l00428"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a4052b590b03f222f9e9b71ef5a75cba9"> 428</a></span><span class="keywordtype">bool</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a4052b590b03f222f9e9b71ef5a75cba9">ompl::geometric::ATRRT::minExpansionControl</a>(<span class="keywordtype">double</span> randMotionDistance)</div>
<div class="line"><a id="l00429" name="l00429"></a><span class="lineno"> 429</span>{</div>
<div class="line"><a id="l00430" name="l00430"></a><span class="lineno"> 430</span> <span class="keywordflow">if</span> (randMotionDistance > <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">frontierThreshold_</a>)</div>
<div class="line"><a id="l00431" name="l00431"></a><span class="lineno"> 431</span> {</div>
<div class="line"><a id="l00432" name="l00432"></a><span class="lineno"> 432</span> <span class="comment">// participates in the tree expansion</span></div>
<div class="line"><a id="l00433" name="l00433"></a><span class="lineno"> 433</span> ++<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a88b0c1c157f86da8abcf0893df538886">frontierCount_</a>;</div>
<div class="line"><a id="l00434" name="l00434"></a><span class="lineno"> 434</span> </div>
<div class="line"><a id="l00435" name="l00435"></a><span class="lineno"> 435</span> <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a id="l00436" name="l00436"></a><span class="lineno"> 436</span> }</div>
<div class="line"><a id="l00437" name="l00437"></a><span class="lineno"> 437</span> <span class="keywordflow">else</span></div>
<div class="line"><a id="l00438" name="l00438"></a><span class="lineno"> 438</span> {</div>
<div class="line"><a id="l00439" name="l00439"></a><span class="lineno"> 439</span> <span class="comment">// participates in the tree refinement</span></div>
<div class="line"><a id="l00440" name="l00440"></a><span class="lineno"> 440</span> </div>
<div class="line"><a id="l00441" name="l00441"></a><span class="lineno"> 441</span> <span class="comment">// check our ratio first before accepting it</span></div>
<div class="line"><a id="l00442" name="l00442"></a><span class="lineno"> 442</span> <span class="keywordflow">if</span> ((<span class="keywordtype">double</span>)<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a2b641a42faab77cdf385ed1232fefa8e">nonfrontierCount_</a> / (<span class="keywordtype">double</span>)<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a88b0c1c157f86da8abcf0893df538886">frontierCount_</a> > <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ab7ea6b5269d2e02e06387b0fa4643b37">frontierNodeRatio_</a>)</div>
<div class="line"><a id="l00443" name="l00443"></a><span class="lineno"> 443</span> <span class="comment">// reject this node as being too much refinement</span></div>
<div class="line"><a id="l00444" name="l00444"></a><span class="lineno"> 444</span> <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a id="l00445" name="l00445"></a><span class="lineno"> 445</span> </div>
<div class="line"><a id="l00446" name="l00446"></a><span class="lineno"> 446</span> ++<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a2b641a42faab77cdf385ed1232fefa8e">nonfrontierCount_</a>;</div>
<div class="line"><a id="l00447" name="l00447"></a><span class="lineno"> 447</span> <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a id="l00448" name="l00448"></a><span class="lineno"> 448</span> }</div>
<div class="line"><a id="l00449" name="l00449"></a><span class="lineno"> 449</span>}</div>
</div>
<div class="line"><a id="l00450" name="l00450"></a><span class="lineno"> 450</span> </div>
<div class="foldopen" id="foldopen00451" data-start="{" data-end="}">
<div class="line"><a id="l00451" name="l00451"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#ae38e1715b076afe492b47615a9e05d5c"> 451</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ae38e1715b076afe492b47615a9e05d5c">ompl::geometric::ATRRT::addUsefulCycles</a>(<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *newMotion, <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *nearMotion)</div>
<div class="line"><a id="l00452" name="l00452"></a><span class="lineno"> 452</span>{</div>
<div class="line"><a id="l00453" name="l00453"></a><span class="lineno"> 453</span> <span class="comment">// neighborhood radius</span></div>
<div class="line"><a id="l00454" name="l00454"></a><span class="lineno"> 454</span> <span class="comment">// double n = static_cast<double>(nearestNeighbors_->size()); // number of nodes in tree</span></div>
<div class="line"><a id="l00455" name="l00455"></a><span class="lineno"> 455</span> <span class="comment">// double d = static_cast<double>(si_->getStateDimension()); // dimension of state space</span></div>
<div class="line"><a id="l00456" name="l00456"></a><span class="lineno"> 456</span> <span class="comment">// double radius = gamma_ * std::pow((std::log(n) / n), 1.0 / d);</span></div>
<div class="line"><a id="l00457" name="l00457"></a><span class="lineno"> 457</span> <span class="comment">// TODO: This is a temporary solution to avoid the issue of the radius being too small</span></div>
<div class="line"><a id="l00458" name="l00458"></a><span class="lineno"> 458</span> <span class="keywordtype">double</span> radius = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a66efb0d2f4e6f0ac5d99590c70073180">neighborhoodRadiusFactor_</a> * <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">maxDistance_</a>;</div>
<div class="line"><a id="l00459" name="l00459"></a><span class="lineno"> 459</span> </div>
<div class="line"><a id="l00460" name="l00460"></a><span class="lineno"> 460</span> std::vector<Motion *> candidates;</div>
<div class="line"><a id="l00461" name="l00461"></a><span class="lineno"> 461</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">nearestNeighbors_</a>->nearestR(newMotion, radius, candidates);</div>
<div class="line"><a id="l00462" name="l00462"></a><span class="lineno"> 462</span> </div>
<div class="line"><a id="l00463" name="l00463"></a><span class="lineno"> 463</span> <span class="keywordflow">for</span> (<span class="keyword">auto</span> *candidate : candidates)</div>
<div class="line"><a id="l00464" name="l00464"></a><span class="lineno"> 464</span> {</div>
<div class="line"><a id="l00465" name="l00465"></a><span class="lineno"> 465</span> <span class="comment">// Skip if neighbor is the same as motion</span></div>
<div class="line"><a id="l00466" name="l00466"></a><span class="lineno"> 466</span> <span class="keywordflow">if</span> (candidate == newMotion || candidate == nearMotion)</div>
<div class="line"><a id="l00467" name="l00467"></a><span class="lineno"> 467</span> <span class="keywordflow">continue</span>;</div>
<div class="line"><a id="l00468" name="l00468"></a><span class="lineno"> 468</span> </div>
<div class="line"><a id="l00469" name="l00469"></a><span class="lineno"> 469</span> <span class="comment">// Cost of direct path between newMotion and neighbor</span></div>
<div class="line"><a id="l00470" name="l00470"></a><span class="lineno"> 470</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> costSpace = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->motionCost(newMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>, candidate->state);</div>
<div class="line"><a id="l00471" name="l00471"></a><span class="lineno"> 471</span> </div>
<div class="line"><a id="l00472" name="l00472"></a><span class="lineno"> 472</span> <span class="comment">// Cost of existing path in the graph</span></div>
<div class="line"><a id="l00473" name="l00473"></a><span class="lineno"> 473</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> costGraph = <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a2413695bae6c5069282069386be0a62a">computeCostLowestCostPath</a>(candidate, newMotion);</div>
<div class="line"><a id="l00474" name="l00474"></a><span class="lineno"> 474</span> </div>
<div class="line"><a id="l00475" name="l00475"></a><span class="lineno"> 475</span> <span class="keywordflow">if</span> ((<a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->isCostBetterThan(costSpace, costGraph)) && <a class="code hl_variable" href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">si_</a>->checkMotion(candidate->state, newMotion-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>))</div>
<div class="line"><a id="l00476" name="l00476"></a><span class="lineno"> 476</span> {</div>
<div class="line"><a id="l00477" name="l00477"></a><span class="lineno"> 477</span> <span class="comment">// Add edge to the graph</span></div>
<div class="line"><a id="l00478" name="l00478"></a><span class="lineno"> 478</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ae8d7a530bfa540df794e6dbdffa9ab56">addEdge</a>(newMotion, candidate);</div>
<div class="line"><a id="l00479" name="l00479"></a><span class="lineno"> 479</span> }</div>
<div class="line"><a id="l00480" name="l00480"></a><span class="lineno"> 480</span> }</div>
<div class="line"><a id="l00481" name="l00481"></a><span class="lineno"> 481</span>}</div>
</div>
<div class="line"><a id="l00482" name="l00482"></a><span class="lineno"> 482</span> </div>
<div class="foldopen" id="foldopen00483" data-start="{" data-end="}">
<div class="line"><a id="l00483" name="l00483"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#ae8d7a530bfa540df794e6dbdffa9ab56"> 483</a></span><span class="keywordtype">void</span> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ae8d7a530bfa540df794e6dbdffa9ab56">ompl::geometric::ATRRT::addEdge</a>(<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *a, <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *b)</div>
<div class="line"><a id="l00484" name="l00484"></a><span class="lineno"> 484</span>{</div>
<div class="line"><a id="l00485" name="l00485"></a><span class="lineno"> 485</span> a->neighbors.push_back(b);</div>
<div class="line"><a id="l00486" name="l00486"></a><span class="lineno"> 486</span> b->neighbors.push_back(a);</div>
<div class="line"><a id="l00487" name="l00487"></a><span class="lineno"> 487</span>}</div>
</div>
<div class="line"><a id="l00488" name="l00488"></a><span class="lineno"> 488</span> </div>
<div class="foldopen" id="foldopen00489" data-start="{" data-end="}">
<div class="line"><a id="l00489" name="l00489"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#ad0dd091ed089ab90023125579582bc72"> 489</a></span>std::vector<ompl::geometric::ATRRT::Motion *> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ad0dd091ed089ab90023125579582bc72">ompl::geometric::ATRRT::computeDijkstraLowestCostPath</a>(<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *a,</div>
<div class="line"><a id="l00490" name="l00490"></a><span class="lineno"> 490</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *b)</div>
<div class="line"><a id="l00491" name="l00491"></a><span class="lineno"> 491</span>{</div>
<div class="line"><a id="l00492" name="l00492"></a><span class="lineno"> 492</span> std::priority_queue<std::pair<Motion *, base::Cost>, std::vector<std::pair<Motion *, base::Cost>>,</div>
<div class="line"><a id="l00493" name="l00493"></a><span class="lineno"> 493</span> <a class="code hl_struct" href="structompl_1_1geometric_1_1ATRRT_1_1MotionCostComparator.html">MotionCostComparator</a>></div>
<div class="line"><a id="l00494" name="l00494"></a><span class="lineno"> 494</span> pq;</div>
<div class="line"><a id="l00495" name="l00495"></a><span class="lineno"> 495</span> std::unordered_map<Motion *, base::Cost> costMap;</div>
<div class="line"><a id="l00496" name="l00496"></a><span class="lineno"> 496</span> std::unordered_map<Motion *, Motion *> parentMap;</div>
<div class="line"><a id="l00497" name="l00497"></a><span class="lineno"> 497</span> </div>
<div class="line"><a id="l00498" name="l00498"></a><span class="lineno"> 498</span> pq.push({a, <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->identityCost()});</div>
<div class="line"><a id="l00499" name="l00499"></a><span class="lineno"> 499</span> costMap[a] = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->identityCost();</div>
<div class="line"><a id="l00500" name="l00500"></a><span class="lineno"> 500</span> parentMap[a] = <span class="keyword">nullptr</span>;</div>
<div class="line"><a id="l00501" name="l00501"></a><span class="lineno"> 501</span> </div>
<div class="line"><a id="l00502" name="l00502"></a><span class="lineno"> 502</span> <span class="keywordflow">while</span> (!pq.empty())</div>
<div class="line"><a id="l00503" name="l00503"></a><span class="lineno"> 503</span> {</div>
<div class="line"><a id="l00504" name="l00504"></a><span class="lineno"> 504</span> <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *current = pq.top().first;</div>
<div class="line"><a id="l00505" name="l00505"></a><span class="lineno"> 505</span> pq.pop();</div>
<div class="line"><a id="l00506" name="l00506"></a><span class="lineno"> 506</span> </div>
<div class="line"><a id="l00507" name="l00507"></a><span class="lineno"> 507</span> <span class="keywordflow">if</span> (current == b)</div>
<div class="line"><a id="l00508" name="l00508"></a><span class="lineno"> 508</span> <span class="keywordflow">break</span>;</div>
<div class="line"><a id="l00509" name="l00509"></a><span class="lineno"> 509</span> </div>
<div class="line"><a id="l00510" name="l00510"></a><span class="lineno"> 510</span> <span class="keywordflow">for</span> (<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *neighbor : current-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a2f743350da9a76fc5cace7c41448c675">neighbors</a>)</div>
<div class="line"><a id="l00511" name="l00511"></a><span class="lineno"> 511</span> {</div>
<div class="line"><a id="l00512" name="l00512"></a><span class="lineno"> 512</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> newCost =</div>
<div class="line"><a id="l00513" name="l00513"></a><span class="lineno"> 513</span> <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->combineCosts(costMap[current], <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->motionCost(current->state, neighbor-><a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">state</a>));</div>
<div class="line"><a id="l00514" name="l00514"></a><span class="lineno"> 514</span> <span class="keywordflow">if</span> (costMap.find(neighbor) == costMap.end() || <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->isCostBetterThan(newCost, costMap[neighbor]))</div>
<div class="line"><a id="l00515" name="l00515"></a><span class="lineno"> 515</span> {</div>
<div class="line"><a id="l00516" name="l00516"></a><span class="lineno"> 516</span> costMap[neighbor] = newCost;</div>
<div class="line"><a id="l00517" name="l00517"></a><span class="lineno"> 517</span> parentMap[neighbor] = current;</div>
<div class="line"><a id="l00518" name="l00518"></a><span class="lineno"> 518</span> pq.push({neighbor, newCost});</div>
<div class="line"><a id="l00519" name="l00519"></a><span class="lineno"> 519</span> }</div>
<div class="line"><a id="l00520" name="l00520"></a><span class="lineno"> 520</span> }</div>
<div class="line"><a id="l00521" name="l00521"></a><span class="lineno"> 521</span> }</div>
<div class="line"><a id="l00522" name="l00522"></a><span class="lineno"> 522</span> </div>
<div class="line"><a id="l00523" name="l00523"></a><span class="lineno"> 523</span> std::vector<Motion *> path;</div>
<div class="line"><a id="l00524" name="l00524"></a><span class="lineno"> 524</span> <span class="keywordflow">for</span> (<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *m = b; m != <span class="keyword">nullptr</span>; m = parentMap[m])</div>
<div class="line"><a id="l00525" name="l00525"></a><span class="lineno"> 525</span> path.push_back(m);</div>
<div class="line"><a id="l00526" name="l00526"></a><span class="lineno"> 526</span> </div>
<div class="line"><a id="l00527" name="l00527"></a><span class="lineno"> 527</span> std::reverse(path.begin(), path.end());</div>
<div class="line"><a id="l00528" name="l00528"></a><span class="lineno"> 528</span> <span class="keywordflow">return</span> path;</div>
<div class="line"><a id="l00529" name="l00529"></a><span class="lineno"> 529</span>}</div>
</div>
<div class="line"><a id="l00530" name="l00530"></a><span class="lineno"> 530</span> </div>
<div class="foldopen" id="foldopen00531" data-start="{" data-end="}">
<div class="line"><a id="l00531" name="l00531"></a><span class="lineno"><a class="line" href="classompl_1_1geometric_1_1ATRRT.html#a2413695bae6c5069282069386be0a62a"> 531</a></span><a class="code hl_class" href="classompl_1_1base_1_1Cost.html">ompl::base::Cost</a> <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#a2413695bae6c5069282069386be0a62a">ompl::geometric::ATRRT::computeCostLowestCostPath</a>(<a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *a, <a class="code hl_class" href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">Motion</a> *b)</div>
<div class="line"><a id="l00532" name="l00532"></a><span class="lineno"> 532</span>{</div>
<div class="line"><a id="l00533" name="l00533"></a><span class="lineno"> 533</span> std::vector<Motion *> path = <a class="code hl_function" href="classompl_1_1geometric_1_1ATRRT.html#ad0dd091ed089ab90023125579582bc72">computeDijkstraLowestCostPath</a>(a, b);</div>
<div class="line"><a id="l00534" name="l00534"></a><span class="lineno"> 534</span> <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a> pathCost = <a class="code hl_class" href="classompl_1_1base_1_1Cost.html">base::Cost</a>{0.0};</div>
<div class="line"><a id="l00535" name="l00535"></a><span class="lineno"> 535</span> <span class="keywordflow">for</span> (<span class="keywordtype">size_t</span> i = 1; i < path.size(); ++i)</div>
<div class="line"><a id="l00536" name="l00536"></a><span class="lineno"> 536</span> pathCost = <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->combineCosts(pathCost, <a class="code hl_variable" href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">opt_</a>->motionCost(path[i - 1]->state, path[i]->state));</div>
<div class="line"><a id="l00537" name="l00537"></a><span class="lineno"> 537</span> <span class="keywordflow">return</span> pathCost;</div>
<div class="line"><a id="l00538" name="l00538"></a><span class="lineno"> 538</span>}</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#l00047">Cost.h:48</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#l00056">Cost.h:56</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#l00047">GoalSampleableRegion.h:48</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#l00062">Goal.h:63</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Goal_html_a02ba4ba487714cd4e8f67c9d4164d0ec"><div class="ttname"><a href="classompl_1_1base_1_1Goal.html#a02ba4ba487714cd4e8f67c9d4164d0ec">ompl::base::Goal::isSatisfied</a></div><div class="ttdeci">virtual bool isSatisfied(const State *st) const =0</div><div class="ttdoc">Return true if the state satisfies the goal constraints.</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#l00058">PlannerData.h:59</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html">ompl::base::PlannerData</a></div><div class="ttdoc">Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...</div><div class="ttdef"><b>Definition</b> <a href="base_2PlannerData_8h_source.html#l00174">PlannerData.h:175</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_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#l00405">PlannerData.cpp:405</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#l00414">PlannerData.cpp:414</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#l00424">PlannerData.cpp:424</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerTerminationCondition_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerTerminationCondition.html">ompl::base::PlannerTerminationCondition</a></div><div class="ttdoc">Encapsulate a termination condition for a motion planner. Planners will call operator() to decide whe...</div><div class="ttdef"><b>Definition</b> <a href="PlannerTerminationCondition_8h_source.html#l00063">PlannerTerminationCondition.h:64</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_a1c6ac45d44026aae6df87f3295d67436"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#a1c6ac45d44026aae6df87f3295d67436">ompl::base::Planner::pis_</a></div><div class="ttdeci">PlannerInputStates pis_</div><div class="ttdoc">Utility class to extract valid input states.</div><div class="ttdef"><b>Definition</b> <a href="Planner_8h_source.html#l00407">Planner.h:407</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#l00413">Planner.h:413</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_a6bbb3dcc3d1604977e319d52c16ef7e5"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#a6bbb3dcc3d1604977e319d52c16ef7e5">ompl::base::Planner::pdef_</a></div><div class="ttdeci">ProblemDefinitionPtr pdef_</div><div class="ttdoc">The user set problem definition.</div><div class="ttdef"><b>Definition</b> <a href="Planner_8h_source.html#l00404">Planner.h:404</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_a9bdea814a817637bd8e6f959c65ceaf9"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#a9bdea814a817637bd8e6f959c65ceaf9">ompl::base::Planner::getName</a></div><div class="ttdeci">const std::string & getName() const</div><div class="ttdoc">Get the name of the planner.</div><div class="ttdef"><b>Definition</b> <a href="Planner_8cpp_source.html#l00056">Planner.cpp:56</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_aa3ceb9471163b6c96f6eeadbcfd3694e"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#aa3ceb9471163b6c96f6eeadbcfd3694e">ompl::base::Planner::si_</a></div><div class="ttdeci">SpaceInformationPtr si_</div><div class="ttdoc">The space information for which planning is done.</div><div class="ttdef"><b>Definition</b> <a href="Planner_8h_source.html#l00401">Planner.h:401</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_ab416900477cf4499139c01f35663dffb"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#ab416900477cf4499139c01f35663dffb">ompl::base::Planner::checkValidity</a></div><div class="ttdeci">virtual void checkValidity()</div><div class="ttdoc">Check to see if the planner is in a working state (setup has been called, a goal was set,...</div><div class="ttdef"><b>Definition</b> <a href="Planner_8cpp_source.html#l00106">Planner.cpp:106</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1State_html"><div class="ttname"><a href="classompl_1_1base_1_1State.html">ompl::base::State</a></div><div class="ttdoc">Definition of an abstract state.</div><div class="ttdef"><b>Definition</b> <a href="base_2State_8h_source.html#l00049">State.h:50</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_1_1Motion_html"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html">ompl::geometric::ATRRT::Motion</a></div><div class="ttdoc">Representation of a motion.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00227">ATRRT.h:228</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_1_1Motion_html_a2f743350da9a76fc5cace7c41448c675"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a2f743350da9a76fc5cace7c41448c675">ompl::geometric::ATRRT::Motion::neighbors</a></div><div class="ttdeci">std::vector< Motion * > neighbors</div><div class="ttdoc">The connected motions in the exploration graph.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00243">ATRRT.h:243</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_1_1Motion_html_a7030ca01a8a2b6fb7393715f14f6a332"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT_1_1Motion.html#a7030ca01a8a2b6fb7393715f14f6a332">ompl::geometric::ATRRT::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="ATRRT_8h_source.html#l00240">ATRRT.h:240</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a00002b925937b02bbab8b9381bdb9f4d"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a00002b925937b02bbab8b9381bdb9f4d">ompl::geometric::ATRRT::frontierThreshold_</a></div><div class="ttdeci">double frontierThreshold_</div><div class="ttdoc">The distance between an old state and a new state that qualifies it as a frontier state.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00353">ATRRT.h:353</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a001b5e82ceda23f33b1fe91806186c9c"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a001b5e82ceda23f33b1fe91806186c9c">ompl::geometric::ATRRT::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="ATRRT_8h_source.html#l00162">ATRRT.h:162</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a0794efa962d0bd2d6a649a540246ca45"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a0794efa962d0bd2d6a649a540246ca45">ompl::geometric::ATRRT::worstCost_</a></div><div class="ttdeci">base::Cost worstCost_</div><div class="ttdoc">The least desirable (e.g., maximum) cost value in the search tree.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00322">ATRRT.h:322</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a0cf84d2efcb75476bf739a8313a69fd7"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a0cf84d2efcb75476bf739a8313a69fd7">ompl::geometric::ATRRT::getFrontierNodeRatio</a></div><div class="ttdeci">double getFrontierNodeRatio() const</div><div class="ttdoc">Get the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfr...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00204">ATRRT.h:204</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a1089e25c891776765a85f2ecec27cd2f"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a1089e25c891776765a85f2ecec27cd2f">ompl::geometric::ATRRT::setGoalBias</a></div><div class="ttdeci">void setGoalBias(double goalBias)</div><div class="ttdoc">Set the goal bias.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00108">ATRRT.h:108</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a145ead99c3474e400883c62edea2ad96"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a145ead99c3474e400883c62edea2ad96">ompl::geometric::ATRRT::getInitTemperature</a></div><div class="ttdeci">double getInitTemperature() const</div><div class="ttdoc">Get the temperature at the start of planning.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00176">ATRRT.h:176</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a15f3084ba584ab73339055c692dd2a44"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a15f3084ba584ab73339055c692dd2a44">ompl::geometric::ATRRT::distanceFunction</a></div><div class="ttdeci">double distanceFunction(const Motion *a, const Motion *b) const</div><div class="ttdoc">Compute distance between motions (actually distance between contained states).</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00253">ATRRT.h:253</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a1a545759535dd51d4bd470d797583c4a"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a1a545759535dd51d4bd470d797583c4a">ompl::geometric::ATRRT::opt_</a></div><div class="ttdeci">ompl::base::OptimizationObjectivePtr opt_</div><div class="ttdoc">The optimization objective being optimized by ATRRT.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00335">ATRRT.h:335</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a1e6216de2a4230256b0396a30155b7d0"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a1e6216de2a4230256b0396a30155b7d0">ompl::geometric::ATRRT::lastGoalMotion_</a></div><div class="ttdeci">Motion * lastGoalMotion_</div><div class="ttdoc">The most recent goal motion. Used for PlannerData computation.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00295">ATRRT.h:295</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a2413695bae6c5069282069386be0a62a"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a2413695bae6c5069282069386be0a62a">ompl::geometric::ATRRT::computeCostLowestCostPath</a></div><div class="ttdeci">ompl::base::Cost computeCostLowestCostPath(Motion *a, Motion *b)</div><div class="ttdoc">Compute cost of lowest-cost path found by Dijkstra.</div><div class="ttdef"><b>Definition</b> <a href="#l00531">ATRRT.cpp:531</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a2653af9be56df732b1f025beee47186a"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a2653af9be56df732b1f025beee47186a">ompl::geometric::ATRRT::goalBias_</a></div><div class="ttdeci">double goalBias_</div><div class="ttdoc">The fraction of time the goal is picked as the state to expand towards (if such a state is available)...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00286">ATRRT.h:286</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a27d454a5a9dbd74dbddca2a278ddbf72"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a27d454a5a9dbd74dbddca2a278ddbf72">ompl::geometric::ATRRT::setInitTemperature</a></div><div class="ttdeci">void setInitTemperature(double initTemperature)</div><div class="ttdoc">Set the initial temperature at the beginning of the algorithm. Should be high to allow for initial ex...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00169">ATRRT.h:169</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a2b641a42faab77cdf385ed1232fefa8e"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a2b641a42faab77cdf385ed1232fefa8e">ompl::geometric::ATRRT::nonfrontierCount_</a></div><div class="ttdeci">double nonfrontierCount_</div><div class="ttdoc">The number of non-frontier nodes in the search tree.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00348">ATRRT.h:348</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a2c20fbc4a2f83292f2b3fc8f3e23b4c2"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a2c20fbc4a2f83292f2b3fc8f3e23b4c2">ompl::geometric::ATRRT::ATRRT</a></div><div class="ttdeci">ATRRT(const base::SpaceInformationPtr &si)</div><div class="ttdoc">Constructor.</div><div class="ttdef"><b>Definition</b> <a href="#l00044">ATRRT.cpp:44</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a329c36cd4c51bb4af3da7387e214edca"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a329c36cd4c51bb4af3da7387e214edca">ompl::geometric::ATRRT::getGoalBias</a></div><div class="ttdeci">double getGoalBias() const</div><div class="ttdoc">Get the goal bias the planner is using.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00114">ATRRT.h:114</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a3736b8795b366bd8254bf25a26b879e5"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a3736b8795b366bd8254bf25a26b879e5">ompl::geometric::ATRRT::transitionTest</a></div><div class="ttdeci">bool transitionTest(const base::Cost &motionCost)</div><div class="ttdoc">Filter irrelevant configuration regarding the search of low-cost paths before inserting into tree.</div><div class="ttdef"><b>Definition</b> <a href="#l00401">ATRRT.cpp:401</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a3be7868273f5d5854961da6b604a3dda"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a3be7868273f5d5854961da6b604a3dda">ompl::geometric::ATRRT::freeMemory</a></div><div class="ttdeci">void freeMemory()</div><div class="ttdoc">Free the memory allocated by this planner.</div><div class="ttdef"><b>Definition</b> <a href="#l00132">ATRRT.cpp:132</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a4052b590b03f222f9e9b71ef5a75cba9"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a4052b590b03f222f9e9b71ef5a75cba9">ompl::geometric::ATRRT::minExpansionControl</a></div><div class="ttdeci">bool minExpansionControl(double randMotionDistance)</div><div class="ttdoc">Use ratio to prefer frontier nodes to nonfrontier ones.</div><div class="ttdef"><b>Definition</b> <a href="#l00428">ATRRT.cpp:428</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a4052ff76eb08eaad5778c8068f1be913"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a4052ff76eb08eaad5778c8068f1be913">ompl::geometric::ATRRT::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 that state as being a fr...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00190">ATRRT.h:190</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a525f4129d7e241219900b2b170a9f262"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a525f4129d7e241219900b2b170a9f262">ompl::geometric::ATRRT::setRange</a></div><div class="ttdeci">void setRange(double distance)</div><div class="ttdoc">Set the range the planner is supposed to use.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00124">ATRRT.h:124</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a55908a440d150d8fcf80d807186312dd"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a55908a440d150d8fcf80d807186312dd">ompl::geometric::ATRRT::sampler_</a></div><div class="ttdeci">base::StateSamplerPtr sampler_</div><div class="ttdoc">State sampler.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00279">ATRRT.h:279</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a5910cd2a91e3887cbfea5f4419629aff"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a5910cd2a91e3887cbfea5f4419629aff">ompl::geometric::ATRRT::temp_</a></div><div class="ttdeci">double temp_</div><div class="ttdoc">Temperature parameter used to control the difficulty level of transition tests. Low temperatures limi...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00316">ATRRT.h:316</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a66efb0d2f4e6f0ac5d99590c70073180"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a66efb0d2f4e6f0ac5d99590c70073180">ompl::geometric::ATRRT::neighborhoodRadiusFactor_</a></div><div class="ttdeci">double neighborhoodRadiusFactor_</div><div class="ttdoc">Factor of maxDistance_ used to calculate neighborhood radius TODO: temporary solution.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00344">ATRRT.h:344</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a7780cbf89c2a050a956d372eac756de4"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a7780cbf89c2a050a956d372eac756de4">ompl::geometric::ATRRT::bestCost_</a></div><div class="ttdeci">base::Cost bestCost_</div><div class="ttdoc">The most desirable (e.g., minimum) cost value in the search tree.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00319">ATRRT.h:319</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a7783b8ccce31900311db46b46267fa37"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a7783b8ccce31900311db46b46267fa37">ompl::geometric::ATRRT::maxDistance_</a></div><div class="ttdeci">double maxDistance_</div><div class="ttdoc">The maximum length of a motion to be added to a tree.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00289">ATRRT.h:289</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a79e6f480ac6c6a53b7c8ad05082bde53"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a79e6f480ac6c6a53b7c8ad05082bde53">ompl::geometric::ATRRT::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="#l00380">ATRRT.cpp:380</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a7c5d3ef6b42f04b9055f00a6de3f47c5"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a7c5d3ef6b42f04b9055f00a6de3f47c5">ompl::geometric::ATRRT::setFrontierThreshold</a></div><div class="ttdeci">void setFrontierThreshold(double frontier_threshold)</div><div class="ttdoc">Set the distance between a new state and the nearest neighbor that qualifies that state as being a fr...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00183">ATRRT.h:183</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a8358273025a7acd5eb3a6e888344ebba"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a8358273025a7acd5eb3a6e888344ebba">ompl::geometric::ATRRT::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="#l00075">ATRRT.cpp:75</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a838a67a4af1929606ff32221de7f9fe1"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a838a67a4af1929606ff32221de7f9fe1">ompl::geometric::ATRRT::costThreshold_</a></div><div class="ttdeci">base::Cost costThreshold_</div><div class="ttdoc">All motion costs must be better than this cost (default is infinity).</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00325">ATRRT.h:325</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a88b0c1c157f86da8abcf0893df538886"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a88b0c1c157f86da8abcf0893df538886">ompl::geometric::ATRRT::frontierCount_</a></div><div class="ttdeci">double frontierCount_</div><div class="ttdoc">The number of frontier nodes in the search tree.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00350">ATRRT.h:350</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_a924f31761622fe7aafc313546c9542ee"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#a924f31761622fe7aafc313546c9542ee">ompl::geometric::ATRRT::solve</a></div><div class="ttdeci">base::PlannerStatus solve(const base::PlannerTerminationCondition &plannerTerminationCondition) 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="#l00148">ATRRT.cpp:148</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_aa9678bc4ff0b83291112cbd7a3d21f87"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#aa9678bc4ff0b83291112cbd7a3d21f87">ompl::geometric::ATRRT::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="ATRRT_8h_source.html#l00130">ATRRT.h:130</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_aaa7b4cc7106a62f9f0f3f2c66ceba621"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#aaa7b4cc7106a62f9f0f3f2c66ceba621">ompl::geometric::ATRRT::getTempChangeFactor</a></div><div class="ttdeci">double getTempChangeFactor() const</div><div class="ttdoc">Get the factor by which the temperature rises based on current acceptance/rejection rate.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00146">ATRRT.h:146</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ab648a6f0de2d4f8f2425f6ae4facff86"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ab648a6f0de2d4f8f2425f6ae4facff86">ompl::geometric::ATRRT::rng_</a></div><div class="ttdeci">RNG rng_</div><div class="ttdoc">The random number generator.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00292">ATRRT.h:292</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ab7ea6b5269d2e02e06387b0fa4643b37"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ab7ea6b5269d2e02e06387b0fa4643b37">ompl::geometric::ATRRT::frontierNodeRatio_</a></div><div class="ttdeci">double frontierNodeRatio_</div><div class="ttdoc">Target ratio of non-frontier nodes to frontier nodes. rho.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00355">ATRRT.h:355</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ac190ee401a05c61192b5f7ca7b04b4d9"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ac190ee401a05c61192b5f7ca7b04b4d9">ompl::geometric::ATRRT::initTemperature_</a></div><div class="ttdeci">double initTemperature_</div><div class="ttdoc">The initial value of temp_.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00332">ATRRT.h:332</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ac4176262e320e87b3d71789e28615b10"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ac4176262e320e87b3d71789e28615b10">ompl::geometric::ATRRT::setFrontierNodeRatio</a></div><div class="ttdeci">void setFrontierNodeRatio(double frontierNodeRatio)</div><div class="ttdoc">Set the ratio between adding nonfrontier nodes to frontier nodes, for example .1 is 1/10 or one nonfr...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00197">ATRRT.h:197</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ac8b09796cfcfa8f78b2df724e55babe1"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ac8b09796cfcfa8f78b2df724e55babe1">ompl::geometric::ATRRT::tempChangeFactor_</a></div><div class="ttdeci">double tempChangeFactor_</div><div class="ttdoc">The value of the expression exp^T_rate. The temperature is increased by this factor whenever the tran...</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00329">ATRRT.h:329</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_acca1522f2f3369560ace3d6761fa9752"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#acca1522f2f3369560ace3d6761fa9752">ompl::geometric::ATRRT::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="#l00092">ATRRT.cpp:92</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ad0dd091ed089ab90023125579582bc72"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ad0dd091ed089ab90023125579582bc72">ompl::geometric::ATRRT::computeDijkstraLowestCostPath</a></div><div class="ttdeci">std::vector< ompl::geometric::ATRRT::Motion * > computeDijkstraLowestCostPath(Motion *a, Motion *b)</div><div class="ttdoc">Compute lowest-cost path in graph between two motions.</div><div class="ttdef"><b>Definition</b> <a href="#l00489">ATRRT.cpp:489</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ad4987c7e6aa146b1f8f00e911efc9588"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ad4987c7e6aa146b1f8f00e911efc9588">ompl::geometric::ATRRT::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="ATRRT_8h_source.html#l00154">ATRRT.h:154</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ad553266f7bda5baa21fd67a1d0f73e21"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ad553266f7bda5baa21fd67a1d0f73e21">ompl::geometric::ATRRT::nearestNeighbors_</a></div><div class="ttdeci">std::shared_ptr< NearestNeighbors< Motion * > > nearestNeighbors_</div><div class="ttdoc">A nearest-neighbors datastructure containing the tree of motions.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00282">ATRRT.h:282</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ae38e1715b076afe492b47615a9e05d5c"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ae38e1715b076afe492b47615a9e05d5c">ompl::geometric::ATRRT::addUsefulCycles</a></div><div class="ttdeci">void addUsefulCycles(Motion *newMotion, Motion *nearMotion)</div><div class="ttdoc">improve solution found by TRRT</div><div class="ttdef"><b>Definition</b> <a href="#l00451">ATRRT.cpp:451</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_ae8d7a530bfa540df794e6dbdffa9ab56"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#ae8d7a530bfa540df794e6dbdffa9ab56">ompl::geometric::ATRRT::addEdge</a></div><div class="ttdeci">void addEdge(Motion *a, Motion *b)</div><div class="ttdoc">Add bidirectional edge between two motions.</div><div class="ttdef"><b>Definition</b> <a href="#l00483">ATRRT.cpp:483</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_aedbccfd472c65277ddc769f030f22ede"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#aedbccfd472c65277ddc769f030f22ede">ompl::geometric::ATRRT::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="ATRRT_8h_source.html#l00140">ATRRT.h:140</a></div></div>
<div class="ttc" id="aclassompl_1_1geometric_1_1ATRRT_html_af59e77284d1fa9c923ceaf29a6eb40b5"><div class="ttname"><a href="classompl_1_1geometric_1_1ATRRT.html#af59e77284d1fa9c923ceaf29a6eb40b5">ompl::geometric::ATRRT::gamma_</a></div><div class="ttdeci">double gamma_</div><div class="ttdoc">Constant derived from the free space volume.</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00340">ATRRT.h:340</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#l00058">SelfConfig.h:59</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1SelfConfig_html_a23f1fef30af80542eeb4709465a06148"><div class="ttname"><a href="classompl_1_1tools_1_1SelfConfig.html#a23f1fef30af80542eeb4709465a06148">ompl::tools::SelfConfig::getDefaultNearestNeighbors</a></div><div class="ttdeci">static NearestNeighbors< _T > * getDefaultNearestNeighbors(const base::Planner *planner)</div><div class="ttdoc">Select a default nearest neighbor datastructure for the given space.</div><div class="ttdef"><b>Definition</b> <a href="SelfConfig_8h_source.html#l00105">SelfConfig.h:105</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="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="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="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="anamespaceompl_1_1base_html"><div class="ttname"><a href="namespaceompl_1_1base.html">ompl::base</a></div><div class="ttdoc">This namespace contains sampling based planning routines shared by both planning under geometric cons...</div><div class="ttdef"><b>Definition</b> <a href="ConstrainedSpaceInformation_8h_source.html#l00054">ConstrainedSpaceInformation.h:55</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#l00079">MagicConstants.h:79</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a></div><div class="ttdoc">A class to store the exit status of Planner::solve().</div><div class="ttdef"><b>Definition</b> <a href="PlannerStatus_8h_source.html#l00048">PlannerStatus.h:49</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_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#l00056">PlannerStatus.h:56</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#l00058">PlannerStatus.h:58</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#l00060">PlannerStatus.h:60</a></div></div>
<div class="ttc" id="astructompl_1_1geometric_1_1ATRRT_1_1MotionCostComparator_html"><div class="ttname"><a href="structompl_1_1geometric_1_1ATRRT_1_1MotionCostComparator.html">ompl::geometric::ATRRT::MotionCostComparator</a></div><div class="ttdoc">bool stating which motion cost is better</div><div class="ttdef"><b>Definition</b> <a href="ATRRT_8h_source.html#l00298">ATRRT.h:299</a></div></div>
</div><!-- fragment --></div><!-- contents -->
</div>
<footer class="footer">
<div class="container">
<a href="http://www.kavrakilab.org">Kavraki Lab</a> •
<a href="https://www.cs.rice.edu">Department of Computer Science</a> •
<a href="https://www.rice.edu">Rice University</a><br/>
Funded in part by the <a href="https://www.nsf.gov">National Science Foundation</a><br/>
Documentation generated by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.16.1
</div>
</footer>
<script>
(function(i,s,o,g,r,a,m){i['GoogleAnalyticsObject']=r;i[r]=i[r]||function(){
(i[r].q=i[r].q||[]).push(arguments)},i[r].l=1*new Date();a=s.createElement(o),
m=s.getElementsByTagName(o)[0];a.async=1;a.src=g;m.parentNode.insertBefore(a,m)
})(window,document,'script','//www.google-analytics.com/analytics.js','ga');
ga('create', 'UA-9156598-2', 'auto');
ga('send', 'pageview');
</script>
<script src="https://cdnjs.cloudflare.com/ajax/libs/popper.js/1.14.7/umd/popper.min.js" integrity="sha384-UO2eT0CpHqdSJQ6hJty5KVphtPhzWj9WO1clHTMGa3JDZwrnQq4sF86dIHNDz0W1" crossorigin="anonymous"></script>
<script src="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/js/bootstrap.min.js" integrity="sha384-JjSmVgyd0p3pXB1rRibZUAYoIIy6OrQ6VrjIEaFf/nJGzIxFDsf4x0xIM+B07jRM" crossorigin="anonymous"></script>
</body>
</html>