-
Notifications
You must be signed in to change notification settings - Fork 1
/
Benchmark_8cpp_source.html
927 lines (925 loc) · 145 KB
/
Benchmark_8cpp_source.html
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
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
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
<!DOCTYPE html>
<html lang="en">
<head>
<meta charset="utf-8">
<meta name="viewport" content="width=device-width, initial-scale=1, shrink-to-fit=no">
<meta name="author" content="Ioan A. Șucan, Mark Moll, Lydia E. Kavraki">
<meta name="generator" content="Doxygen 1.8.17"/>
<title>ompl/tools/benchmark/src/Benchmark.cpp Source File</title>
<link href="tabs.css" rel="stylesheet" type="text/css"/>
<script src="jquery.js"></script>
<script src="dynsections.js"></script>
<link href="search/search.css" rel="stylesheet" type="text/css"/>
<script type="text/javascript" src="search/searchdata.js"></script>
<script type="text/javascript" src="search/search.js"></script>
<script type="text/javascript">
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
$(document).ready(function() { init_search(); });
/* @license-end */
</script>
<script type="text/x-mathjax-config">
MathJax.Hub.Config({
extensions: ["tex2jax.js", "TeX/AMSmath.js", "TeX/AMSsymbols.js"],
jax: ["input/TeX","output/HTML-CSS"],
});
</script>
<script type="text/javascript" async="async" src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/MathJax.js"></script>
<link href="doxygen.css" rel="stylesheet" type="text/css" />
<link rel="stylesheet" href="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/css/bootstrap.min.css" integrity="sha384-ggOyR0iXCbMQv3Xipma34MD+dH/1fQ784/j6cY/iJTQUOhcWr7x9JvoRxT2MZw1T" crossorigin="anonymous">
<link href="ompl.css" rel="stylesheet">
</head>
<body>
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
<nav class="navbar navbar-expand-md fixed-top navbar-dark">
<a class="navbar-brand" href="./index.html">OMPL</a>
<button class="navbar-toggler" type="button" data-toggle="collapse" data-target="#navbar">
<span class="navbar-toggler-icon"></span>
</button>
<div class="collapse navbar-collapse" id="navbar">
<ul class="navbar-nav mr-auto">
<li class="nav-item"><a class="nav-link" href="download.html">Download</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="docDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Documentation</a>
<div class="dropdown-menu" aria-labelledby="docDropdown">
<a class="dropdown-item" href="https://ompl.kavrakilab.org/OMPL_Primer.pdf">Primer</a>
<a class="dropdown-item" href="installation.html">Installation</a>
<a class="dropdown-item" href="tutorials.html">Tutorials</a>
<a class="dropdown-item" href="group__demos.html">Demos</a>
<a class="dropdown-item omplapp" href="gui.html">OMPL.app GUI</a>
<a class="dropdown-item omplapp" href="webapp.html">OMPL web app</a>
<a class="dropdown-item" href="python.html">Python Bindings</a>
<a class="dropdown-item" href="planners.html">Available Planners</a>
<a class="dropdown-item" href="plannerTerminationConditions.html">Planner Termination Conditions</a>
<a class="dropdown-item" href="benchmark.html">Benchmarking Planners</a>
<a class="dropdown-item" href="spaces.html">Available State Spaces</a>
<a class="dropdown-item" href="optimalPlanning.html">Optimal Planning</a>
<a class="dropdown-item" href="constrainedPlanning.html">Constrained Planning</a>
<a class="dropdown-item" href="multiLevelPlanning.html">Multilevel Planning</a>
<a class="dropdown-item" href="FAQ.html">FAQ</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">External links</div>
<a class="dropdown-item" href="http://moveit.ros.org">MoveIt</a>
<a class="dropdown-item" href="http://plannerarena.org">Planner Arena</a>
<a class="dropdown-item" href="https://moveit.ros.org//moveit!/ros/2013/05/07/icra-motion-planning-tutorial.html">ICRA 2013 Tutorial</a>
<a class="dropdown-item" href="http://kavrakilab.org/iros2011/">IROS 2011 Tutorial</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="gallery.html">Gallery</a></li>
<li class="nav-item"><a class="nav-link" href="integration.html">OMPL Integrations</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="codeDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Code</a>
<div class="dropdown-menu" aria-labelledby="codeDropdown">
<a class="dropdown-item" href="api_overview.html">API Overview</a>
<a class="dropdown-item" href="annotated.html">Classes</a>
<a class="dropdown-item" href="files.html">Files</a>
<a class="dropdown-item" href="styleGuide.html">Style Guide</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">Repositories</div>
<a class="dropdown-item" href="https://github.com/ompl/ompl">ompl on GitHub</a>
<a class="dropdown-item" href="https://github.com/ompl/omplapp">omplapp on GitHub</a>
<div class="dropdown-divider"></div>
<div class="dropdown-header">Continuous Integration</div>
<a class="dropdown-item" href="https://travis-ci.org/ompl/ompl">ompl on Travis CI (Linux/macOS)</a>
<a class="dropdown-item" href="https://travis-ci.org/ompl/omplapp">omplapp on Travis CI (Linux/macOS)</a>
<a class="dropdown-item" href="https://ci.appveyor.com/project/mamoll/ompl">ompl on AppVeyor CI (Windows)</a>
<a class="dropdown-item" href="https://ci.appveyor.com/project/mamoll/omplapp">omplapp on AppVeyor CI (Windows)</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://github.com/ompl/ompl/issues">Issues</a></li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="communityDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">Community</a>
<div class="dropdown-menu" aria-labelledby="communityDropdown">
<a class="dropdown-item" href="support.html">Get Support</a>
<a class="dropdown-item" href="developers.html">Developers/Contributors</a>
<a class="dropdown-item" href="contrib.html">Submit a Contribution</a>
<a class="dropdown-item" href="education.html">Education</a>
</div>
</li>
<li class="nav-item dropdown">
<a class="nav-link dropdown-toggle" href="#" id="aboutDropdown" role="button" data-toggle="dropdown" aria-haspopup="true" aria-expanded="false">About</a>
<div class="dropdown-menu" aria-labelledby="aboutDropdown">
<a class="dropdown-item" href="license.html">License</a>
<a class="dropdown-item" href="citations.html">Citations</a>
<a class="dropdown-item" href="acknowledgements.html">Acknowledgments</a>
</div>
</li>
<li class="nav-item"><a class="nav-link" href="https://ompl.kavrakilab.org/blog.html">Blog</a></li>
</ul>
<div id="MSearchBox" class="MSearchBoxInactive">
<span class="left">
<img id="MSearchSelect" src="search/mag_sel.png"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
alt=""/>
<input type="text" id="MSearchField" value="Search" accesskey="S"
onfocus="searchBox.OnSearchFieldFocus(true)"
onblur="searchBox.OnSearchFieldFocus(false)"
onkeyup="searchBox.OnSearchFieldChange(event)"/>
</span><span class="right">
<a id="MSearchClose" href="javascript:searchBox.CloseResultsWindow()"><img id="MSearchCloseImg" border="0" src="search/close.png" alt=""/></a>
</span>
</div>
</div>
</nav>
<div class="container" role="main">
<div>
<!-- Generated by Doxygen 1.8.17 -->
<script type="text/javascript">
/* @license magnet:?xt=urn:btih:cf05388f2679ee054f2beb29a391d25f4e673ac3&dn=gpl-2.0.txt GPL-v2 */
var searchBox = new SearchBox("searchBox", "search",false,'Search');
/* @license-end */
</script>
<!-- window showing the filter options -->
<div id="MSearchSelectWindow"
onmouseover="return searchBox.OnSearchSelectShow()"
onmouseout="return searchBox.OnSearchSelectHide()"
onkeydown="return searchBox.OnSearchSelectKey(event)">
</div>
<!-- iframe showing the search results (closed by default) -->
<div id="MSearchResultsWindow">
<iframe src="javascript:void(0)" frameborder="0"
name="MSearchResults" id="MSearchResults">
</iframe>
</div>
<div id="nav-path" class="navpath">
<ul>
<li class="navelem"><a class="el" href="dir_efdc19d105c21b1223d5f8dc524071be.html">ompl</a></li><li class="navelem"><a class="el" href="dir_51d701e36e5f4db9f689c2919d29bc58.html">tools</a></li><li class="navelem"><a class="el" href="dir_0aa4e861dc119f6b09db3587cb937bed.html">benchmark</a></li><li class="navelem"><a class="el" href="dir_92fec344c2eec5e859e6381dafd26ec4.html">src</a></li> </ul>
</div>
</div><!-- top -->
<div class="header">
<div class="headertitle">
<div class="title">Benchmark.cpp</div> </div>
</div><!--header-->
<div class="contents">
<div class="fragment"><div class="line"><a name="l00001"></a><span class="lineno"> 1</span> <span class="comment">/*********************************************************************</span></div>
<div class="line"><a name="l00002"></a><span class="lineno"> 2</span> <span class="comment">* Software License Agreement (BSD License)</span></div>
<div class="line"><a name="l00003"></a><span class="lineno"> 3</span> <span class="comment">*</span></div>
<div class="line"><a name="l00004"></a><span class="lineno"> 4</span> <span class="comment">* Copyright (c) 2010, Rice University</span></div>
<div class="line"><a name="l00005"></a><span class="lineno"> 5</span> <span class="comment">* All rights reserved.</span></div>
<div class="line"><a name="l00006"></a><span class="lineno"> 6</span> <span class="comment">*</span></div>
<div class="line"><a name="l00007"></a><span class="lineno"> 7</span> <span class="comment">* Redistribution and use in source and binary forms, with or without</span></div>
<div class="line"><a name="l00008"></a><span class="lineno"> 8</span> <span class="comment">* modification, are permitted provided that the following conditions</span></div>
<div class="line"><a name="l00009"></a><span class="lineno"> 9</span> <span class="comment">* are met:</span></div>
<div class="line"><a name="l00010"></a><span class="lineno"> 10</span> <span class="comment">*</span></div>
<div class="line"><a name="l00011"></a><span class="lineno"> 11</span> <span class="comment">* * Redistributions of source code must retain the above copyright</span></div>
<div class="line"><a name="l00012"></a><span class="lineno"> 12</span> <span class="comment">* notice, this list of conditions and the following disclaimer.</span></div>
<div class="line"><a name="l00013"></a><span class="lineno"> 13</span> <span class="comment">* * Redistributions in binary form must reproduce the above</span></div>
<div class="line"><a name="l00014"></a><span class="lineno"> 14</span> <span class="comment">* copyright notice, this list of conditions and the following</span></div>
<div class="line"><a name="l00015"></a><span class="lineno"> 15</span> <span class="comment">* disclaimer in the documentation and/or other materials provided</span></div>
<div class="line"><a name="l00016"></a><span class="lineno"> 16</span> <span class="comment">* with the distribution.</span></div>
<div class="line"><a name="l00017"></a><span class="lineno"> 17</span> <span class="comment">* * Neither the name of the Rice University nor the names of its</span></div>
<div class="line"><a name="l00018"></a><span class="lineno"> 18</span> <span class="comment">* contributors may be used to endorse or promote products derived</span></div>
<div class="line"><a name="l00019"></a><span class="lineno"> 19</span> <span class="comment">* from this software without specific prior written permission.</span></div>
<div class="line"><a name="l00020"></a><span class="lineno"> 20</span> <span class="comment">*</span></div>
<div class="line"><a name="l00021"></a><span class="lineno"> 21</span> <span class="comment">* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS</span></div>
<div class="line"><a name="l00022"></a><span class="lineno"> 22</span> <span class="comment">* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT</span></div>
<div class="line"><a name="l00023"></a><span class="lineno"> 23</span> <span class="comment">* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS</span></div>
<div class="line"><a name="l00024"></a><span class="lineno"> 24</span> <span class="comment">* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE</span></div>
<div class="line"><a name="l00025"></a><span class="lineno"> 25</span> <span class="comment">* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,</span></div>
<div class="line"><a name="l00026"></a><span class="lineno"> 26</span> <span class="comment">* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,</span></div>
<div class="line"><a name="l00027"></a><span class="lineno"> 27</span> <span class="comment">* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;</span></div>
<div class="line"><a name="l00028"></a><span class="lineno"> 28</span> <span class="comment">* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER</span></div>
<div class="line"><a name="l00029"></a><span class="lineno"> 29</span> <span class="comment">* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT</span></div>
<div class="line"><a name="l00030"></a><span class="lineno"> 30</span> <span class="comment">* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN</span></div>
<div class="line"><a name="l00031"></a><span class="lineno"> 31</span> <span class="comment">* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE</span></div>
<div class="line"><a name="l00032"></a><span class="lineno"> 32</span> <span class="comment">* POSSIBILITY OF SUCH DAMAGE.</span></div>
<div class="line"><a name="l00033"></a><span class="lineno"> 33</span> <span class="comment">*********************************************************************/</span></div>
<div class="line"><a name="l00034"></a><span class="lineno"> 34</span>  </div>
<div class="line"><a name="l00035"></a><span class="lineno"> 35</span> <span class="comment">/* Author: Ioan Sucan, Luis G. Torres */</span></div>
<div class="line"><a name="l00036"></a><span class="lineno"> 36</span>  </div>
<div class="line"><a name="l00037"></a><span class="lineno"> 37</span> <span class="preprocessor">#include "ompl/tools/benchmark/Benchmark.h"</span></div>
<div class="line"><a name="l00038"></a><span class="lineno"> 38</span> <span class="preprocessor">#include "ompl/tools/benchmark/MachineSpecs.h"</span></div>
<div class="line"><a name="l00039"></a><span class="lineno"> 39</span> <span class="preprocessor">#include "ompl/util/Time.h"</span></div>
<div class="line"><a name="l00040"></a><span class="lineno"> 40</span> <span class="preprocessor">#include "ompl/config.h"</span></div>
<div class="line"><a name="l00041"></a><span class="lineno"> 41</span> <span class="preprocessor">#include "ompl/util/String.h"</span></div>
<div class="line"><a name="l00042"></a><span class="lineno"> 42</span> <span class="preprocessor">#include <boost/scoped_ptr.hpp></span></div>
<div class="line"><a name="l00043"></a><span class="lineno"> 43</span> <span class="preprocessor">#include <thread></span></div>
<div class="line"><a name="l00044"></a><span class="lineno"> 44</span> <span class="preprocessor">#include <mutex></span></div>
<div class="line"><a name="l00045"></a><span class="lineno"> 45</span> <span class="preprocessor">#include <condition_variable></span></div>
<div class="line"><a name="l00046"></a><span class="lineno"> 46</span> <span class="preprocessor">#include <fstream></span></div>
<div class="line"><a name="l00047"></a><span class="lineno"> 47</span> <span class="preprocessor">#include <sstream></span></div>
<div class="line"><a name="l00048"></a><span class="lineno"> 48</span>  </div>
<div class="line"><a name="l00050"></a><span class="lineno"> 50</span> <span class="keyword">namespace </span><a class="code" href="namespaceompl.html">ompl</a></div>
<div class="line"><a name="l00051"></a><span class="lineno"> 51</span> {</div>
<div class="line"><a name="l00052"></a><span class="lineno"> 52</span>  <span class="keyword">namespace </span>tools</div>
<div class="line"><a name="l00053"></a><span class="lineno"> 53</span>  {</div>
<div class="line"><a name="l00056"></a><span class="lineno"> 56</span>  <span class="keyword">static</span> std::string getResultsFilename(<span class="keyword">const</span> Benchmark::CompleteExperiment &exp)</div>
<div class="line"><a name="l00057"></a><span class="lineno"> 57</span>  {</div>
<div class="line"><a name="l00058"></a><span class="lineno"> 58</span>  <span class="keywordflow">return</span> <span class="stringliteral">"ompl_"</span> + exp.host + <span class="stringliteral">"_"</span> + <a class="code" href="namespaceompl_1_1time.html#ae8d794354a37128403aba90a187fe532">time::as_string</a>(exp.startTime) + <span class="stringliteral">".log"</span>;</div>
<div class="line"><a name="l00059"></a><span class="lineno"> 59</span>  }</div>
<div class="line"><a name="l00060"></a><span class="lineno"> 60</span>  </div>
<div class="line"><a name="l00063"></a><span class="lineno"> 63</span>  <span class="keyword">static</span> std::string getConsoleFilename(<span class="keyword">const</span> Benchmark::CompleteExperiment &exp)</div>
<div class="line"><a name="l00064"></a><span class="lineno"> 64</span>  {</div>
<div class="line"><a name="l00065"></a><span class="lineno"> 65</span>  <span class="keywordflow">return</span> <span class="stringliteral">"ompl_"</span> + exp.host + <span class="stringliteral">"_"</span> + <a class="code" href="namespaceompl_1_1time.html#ae8d794354a37128403aba90a187fe532">time::as_string</a>(exp.startTime) + <span class="stringliteral">".console"</span>;</div>
<div class="line"><a name="l00066"></a><span class="lineno"> 66</span>  }</div>
<div class="line"><a name="l00067"></a><span class="lineno"> 67</span>  </div>
<div class="line"><a name="l00068"></a><span class="lineno"> 68</span>  <span class="keyword">static</span> <span class="keywordtype">bool</span> terminationCondition(<span class="keyword">const</span> <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> maxMem, <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">time::point</a> &endTime)</div>
<div class="line"><a name="l00069"></a><span class="lineno"> 69</span>  {</div>
<div class="line"><a name="l00070"></a><span class="lineno"> 70</span>  <span class="keywordflow">if</span> (<a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() < endTime && <a class="code" href="namespaceompl_1_1machine.html#a263d0e9d43cd9e10edb468b97f46a198">machine::getProcessMemoryUsage</a>() < maxMem)</div>
<div class="line"><a name="l00071"></a><span class="lineno"> 71</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00072"></a><span class="lineno"> 72</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00073"></a><span class="lineno"> 73</span>  }</div>
<div class="line"><a name="l00074"></a><span class="lineno"> 74</span>  </div>
<div class="line"><a name="l00075"></a><span class="lineno"> 75</span>  <span class="keyword">class </span>RunPlanner</div>
<div class="line"><a name="l00076"></a><span class="lineno"> 76</span>  {</div>
<div class="line"><a name="l00077"></a><span class="lineno"> 77</span>  <span class="keyword">public</span>:</div>
<div class="line"><a name="l00078"></a><span class="lineno"> 78</span>  RunPlanner(<span class="keyword">const</span> Benchmark *benchmark)</div>
<div class="line"><a name="l00079"></a><span class="lineno"> 79</span>  : benchmark_(benchmark), timeUsed_(0.0), memUsed_(0)</div>
<div class="line"><a name="l00080"></a><span class="lineno"> 80</span>  {</div>
<div class="line"><a name="l00081"></a><span class="lineno"> 81</span>  }</div>
<div class="line"><a name="l00082"></a><span class="lineno"> 82</span>  </div>
<div class="line"><a name="l00083"></a><span class="lineno"> 83</span>  <span class="keywordtype">void</span> run(<span class="keyword">const</span> base::PlannerPtr &planner, <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> memStart,</div>
<div class="line"><a name="l00084"></a><span class="lineno"> 84</span>  <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> maxMem, <span class="keyword">const</span> <span class="keywordtype">double</span> maxTime, <span class="keyword">const</span> <span class="keywordtype">double</span> timeBetweenUpdates)</div>
<div class="line"><a name="l00085"></a><span class="lineno"> 85</span>  {</div>
<div class="line"><a name="l00086"></a><span class="lineno"> 86</span>  runThread(planner, memStart + maxMem, <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(maxTime), <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(timeBetweenUpdates));</div>
<div class="line"><a name="l00087"></a><span class="lineno"> 87</span>  }</div>
<div class="line"><a name="l00088"></a><span class="lineno"> 88</span>  </div>
<div class="line"><a name="l00089"></a><span class="lineno"> 89</span>  <span class="keywordtype">double</span> getTimeUsed()<span class="keyword"> const</span></div>
<div class="line"><a name="l00090"></a><span class="lineno"> 90</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00091"></a><span class="lineno"> 91</span>  <span class="keywordflow">return</span> timeUsed_;</div>
<div class="line"><a name="l00092"></a><span class="lineno"> 92</span>  }</div>
<div class="line"><a name="l00093"></a><span class="lineno"> 93</span>  </div>
<div class="line"><a name="l00094"></a><span class="lineno"> 94</span>  <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> getMemUsed()<span class="keyword"> const</span></div>
<div class="line"><a name="l00095"></a><span class="lineno"> 95</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00096"></a><span class="lineno"> 96</span>  <span class="keywordflow">return</span> memUsed_;</div>
<div class="line"><a name="l00097"></a><span class="lineno"> 97</span>  }</div>
<div class="line"><a name="l00098"></a><span class="lineno"> 98</span>  </div>
<div class="line"><a name="l00099"></a><span class="lineno"> 99</span>  base::PlannerStatus getStatus()<span class="keyword"> const</span></div>
<div class="line"><a name="l00100"></a><span class="lineno"> 100</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00101"></a><span class="lineno"> 101</span>  <span class="keywordflow">return</span> status_;</div>
<div class="line"><a name="l00102"></a><span class="lineno"> 102</span>  }</div>
<div class="line"><a name="l00103"></a><span class="lineno"> 103</span>  </div>
<div class="line"><a name="l00104"></a><span class="lineno"> 104</span>  <span class="keyword">const</span> Benchmark::RunProgressData &getRunProgressData()<span class="keyword"> const</span></div>
<div class="line"><a name="l00105"></a><span class="lineno"> 105</span> <span class="keyword"> </span>{</div>
<div class="line"><a name="l00106"></a><span class="lineno"> 106</span>  <span class="keywordflow">return</span> runProgressData_;</div>
<div class="line"><a name="l00107"></a><span class="lineno"> 107</span>  }</div>
<div class="line"><a name="l00108"></a><span class="lineno"> 108</span>  </div>
<div class="line"><a name="l00109"></a><span class="lineno"> 109</span>  <span class="keyword">private</span>:</div>
<div class="line"><a name="l00110"></a><span class="lineno"> 110</span>  <span class="keywordtype">void</span> runThread(<span class="keyword">const</span> base::PlannerPtr &planner, <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> maxMem,</div>
<div class="line"><a name="l00111"></a><span class="lineno"> 111</span>  <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1time.html#ae77961d01352b61e3fcd521ec3e5d59a">time::duration</a> &maxDuration, <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1time.html#ae77961d01352b61e3fcd521ec3e5d59a">time::duration</a> &timeBetweenUpdates)</div>
<div class="line"><a name="l00112"></a><span class="lineno"> 112</span>  {</div>
<div class="line"><a name="l00113"></a><span class="lineno"> 113</span>  <a class="code" href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">time::point</a> timeStart = <a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>();</div>
<div class="line"><a name="l00114"></a><span class="lineno"> 114</span>  </div>
<div class="line"><a name="l00115"></a><span class="lineno"> 115</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00116"></a><span class="lineno"> 116</span>  {</div>
<div class="line"><a name="l00117"></a><span class="lineno"> 117</span>  <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">time::point</a> endtime = <a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() + maxDuration;</div>
<div class="line"><a name="l00118"></a><span class="lineno"> 118</span>  <a class="code" href="namespaceompl_1_1base.html#a5c218cde462780a4502dfc561708e903">base::PlannerTerminationConditionFn</a> ptc([maxMem, endtime]</div>
<div class="line"><a name="l00119"></a><span class="lineno"> 119</span>  {</div>
<div class="line"><a name="l00120"></a><span class="lineno"> 120</span>  <span class="keywordflow">return</span> terminationCondition(maxMem, endtime);</div>
<div class="line"><a name="l00121"></a><span class="lineno"> 121</span>  });</div>
<div class="line"><a name="l00122"></a><span class="lineno"> 122</span>  solved_ = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00123"></a><span class="lineno"> 123</span>  <span class="comment">// Only launch the planner progress property</span></div>
<div class="line"><a name="l00124"></a><span class="lineno"> 124</span>  <span class="comment">// collector if there is any data for it to report</span></div>
<div class="line"><a name="l00125"></a><span class="lineno"> 125</span>  <span class="comment">//</span></div>
<div class="line"><a name="l00126"></a><span class="lineno"> 126</span>  <span class="comment">// \todo issue here is that at least one sample</span></div>
<div class="line"><a name="l00127"></a><span class="lineno"> 127</span>  <span class="comment">// always gets taken before planner even starts;</span></div>
<div class="line"><a name="l00128"></a><span class="lineno"> 128</span>  <span class="comment">// might be worth adding a short wait time before</span></div>
<div class="line"><a name="l00129"></a><span class="lineno"> 129</span>  <span class="comment">// collector begins sampling</span></div>
<div class="line"><a name="l00130"></a><span class="lineno"> 130</span>  boost::scoped_ptr<std::thread> t;</div>
<div class="line"><a name="l00131"></a><span class="lineno"> 131</span>  <span class="keywordflow">if</span> (planner->getPlannerProgressProperties().size() > 0)</div>
<div class="line"><a name="l00132"></a><span class="lineno"> 132</span>  t.reset(<span class="keyword">new</span> std::thread([<span class="keyword">this</span>, &planner, timeBetweenUpdates]</div>
<div class="line"><a name="l00133"></a><span class="lineno"> 133</span>  {</div>
<div class="line"><a name="l00134"></a><span class="lineno"> 134</span>  collectProgressProperties(planner->getPlannerProgressProperties(),</div>
<div class="line"><a name="l00135"></a><span class="lineno"> 135</span>  timeBetweenUpdates);</div>
<div class="line"><a name="l00136"></a><span class="lineno"> 136</span>  }));</div>
<div class="line"><a name="l00137"></a><span class="lineno"> 137</span>  status_ = planner->solve(ptc, 0.1);</div>
<div class="line"><a name="l00138"></a><span class="lineno"> 138</span>  solvedFlag_.lock();</div>
<div class="line"><a name="l00139"></a><span class="lineno"> 139</span>  solved_ = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00140"></a><span class="lineno"> 140</span>  solvedCondition_.notify_all();</div>
<div class="line"><a name="l00141"></a><span class="lineno"> 141</span>  solvedFlag_.unlock();</div>
<div class="line"><a name="l00142"></a><span class="lineno"> 142</span>  <span class="keywordflow">if</span> (t)</div>
<div class="line"><a name="l00143"></a><span class="lineno"> 143</span>  t->join(); <span class="comment">// maybe look into interrupting even if planner throws an exception</span></div>
<div class="line"><a name="l00144"></a><span class="lineno"> 144</span>  }</div>
<div class="line"><a name="l00145"></a><span class="lineno"> 145</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00146"></a><span class="lineno"> 146</span>  {</div>
<div class="line"><a name="l00147"></a><span class="lineno"> 147</span>  std::stringstream es;</div>
<div class="line"><a name="l00148"></a><span class="lineno"> 148</span>  es << <span class="stringliteral">"There was an error executing planner "</span> << benchmark_->getStatus().activePlanner</div>
<div class="line"><a name="l00149"></a><span class="lineno"> 149</span>  << <span class="stringliteral">", run = "</span> << benchmark_->getStatus().activeRun << std::endl;</div>
<div class="line"><a name="l00150"></a><span class="lineno"> 150</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00151"></a><span class="lineno"> 151</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00152"></a><span class="lineno"> 152</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00153"></a><span class="lineno"> 153</span>  }</div>
<div class="line"><a name="l00154"></a><span class="lineno"> 154</span>  </div>
<div class="line"><a name="l00155"></a><span class="lineno"> 155</span>  timeUsed_ = <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(<a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() - timeStart);</div>
<div class="line"><a name="l00156"></a><span class="lineno"> 156</span>  memUsed_ = <a class="code" href="namespaceompl_1_1machine.html#a263d0e9d43cd9e10edb468b97f46a198">machine::getProcessMemoryUsage</a>();</div>
<div class="line"><a name="l00157"></a><span class="lineno"> 157</span>  }</div>
<div class="line"><a name="l00158"></a><span class="lineno"> 158</span>  </div>
<div class="line"><a name="l00159"></a><span class="lineno"> 159</span>  <span class="keywordtype">void</span> collectProgressProperties(<span class="keyword">const</span> <a class="code" href="classompl_1_1base_1_1Planner.html#adc4df80108aec5db29373302e4b8d723">base::Planner::PlannerProgressProperties</a> &properties,</div>
<div class="line"><a name="l00160"></a><span class="lineno"> 160</span>  <span class="keyword">const</span> <a class="code" href="namespaceompl_1_1time.html#ae77961d01352b61e3fcd521ec3e5d59a">time::duration</a> &timePerUpdate)</div>
<div class="line"><a name="l00161"></a><span class="lineno"> 161</span>  {</div>
<div class="line"><a name="l00162"></a><span class="lineno"> 162</span>  <a class="code" href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">time::point</a> timeStart = <a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>();</div>
<div class="line"><a name="l00163"></a><span class="lineno"> 163</span>  </div>
<div class="line"><a name="l00164"></a><span class="lineno"> 164</span>  std::unique_lock<std::mutex> ulock(solvedFlag_);</div>
<div class="line"><a name="l00165"></a><span class="lineno"> 165</span>  <span class="keywordflow">while</span> (!solved_)</div>
<div class="line"><a name="l00166"></a><span class="lineno"> 166</span>  {</div>
<div class="line"><a name="l00167"></a><span class="lineno"> 167</span>  <span class="keywordflow">if</span> (solvedCondition_.wait_for(ulock, timePerUpdate) == std::cv_status::no_timeout)</div>
<div class="line"><a name="l00168"></a><span class="lineno"> 168</span>  <span class="keywordflow">return</span>;</div>
<div class="line"><a name="l00169"></a><span class="lineno"> 169</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00170"></a><span class="lineno"> 170</span>  {</div>
<div class="line"><a name="l00171"></a><span class="lineno"> 171</span>  <span class="keywordtype">double</span> timeInSeconds = <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(<a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() - timeStart);</div>
<div class="line"><a name="l00172"></a><span class="lineno"> 172</span>  std::string timeStamp = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(timeInSeconds);</div>
<div class="line"><a name="l00173"></a><span class="lineno"> 173</span>  std::map<std::string, std::string> data;</div>
<div class="line"><a name="l00174"></a><span class="lineno"> 174</span>  data[<span class="stringliteral">"time REAL"</span>] = timeStamp;</div>
<div class="line"><a name="l00175"></a><span class="lineno"> 175</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &property : properties)</div>
<div class="line"><a name="l00176"></a><span class="lineno"> 176</span>  {</div>
<div class="line"><a name="l00177"></a><span class="lineno"> 177</span>  data[<span class="keyword">property</span>.first] = <span class="keyword">property</span>.second();</div>
<div class="line"><a name="l00178"></a><span class="lineno"> 178</span>  }</div>
<div class="line"><a name="l00179"></a><span class="lineno"> 179</span>  runProgressData_.push_back(data);</div>
<div class="line"><a name="l00180"></a><span class="lineno"> 180</span>  }</div>
<div class="line"><a name="l00181"></a><span class="lineno"> 181</span>  }</div>
<div class="line"><a name="l00182"></a><span class="lineno"> 182</span>  }</div>
<div class="line"><a name="l00183"></a><span class="lineno"> 183</span>  </div>
<div class="line"><a name="l00184"></a><span class="lineno"> 184</span>  <span class="keyword">const</span> Benchmark *benchmark_;</div>
<div class="line"><a name="l00185"></a><span class="lineno"> 185</span>  <span class="keywordtype">double</span> timeUsed_;</div>
<div class="line"><a name="l00186"></a><span class="lineno"> 186</span>  <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> memUsed_;</div>
<div class="line"><a name="l00187"></a><span class="lineno"> 187</span>  base::PlannerStatus status_;</div>
<div class="line"><a name="l00188"></a><span class="lineno"> 188</span>  Benchmark::RunProgressData runProgressData_;</div>
<div class="line"><a name="l00189"></a><span class="lineno"> 189</span>  </div>
<div class="line"><a name="l00190"></a><span class="lineno"> 190</span>  <span class="comment">// variables needed for progress property collection</span></div>
<div class="line"><a name="l00191"></a><span class="lineno"> 191</span>  <span class="keywordtype">bool</span> solved_;</div>
<div class="line"><a name="l00192"></a><span class="lineno"> 192</span>  std::mutex solvedFlag_;</div>
<div class="line"><a name="l00193"></a><span class="lineno"> 193</span>  std::condition_variable solvedCondition_;</div>
<div class="line"><a name="l00194"></a><span class="lineno"> 194</span>  };</div>
<div class="line"><a name="l00195"></a><span class="lineno"> 195</span>  }</div>
<div class="line"><a name="l00196"></a><span class="lineno"> 196</span> }</div>
<div class="line"><a name="l00198"></a><span class="lineno"> 198</span>  </div>
<div class="line"><a name="l00199"></a><span class="lineno"><a class="line" href="classompl_1_1tools_1_1Benchmark.html#ac3a46507c4b8f4a3379ecca534f4ca93"> 199</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a979f5df0704b89e7da4a1c29ab857a02">ompl::tools::Benchmark::saveResultsToFile</a>(<span class="keyword">const</span> <span class="keywordtype">char</span> *filename)<span class="keyword"> const</span></div>
<div class="line"><a name="l00200"></a><span class="lineno"> 200</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00201"></a><span class="lineno"> 201</span>  <span class="keywordtype">bool</span> result = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00202"></a><span class="lineno"> 202</span>  </div>
<div class="line"><a name="l00203"></a><span class="lineno"> 203</span>  std::ofstream fout(filename);</div>
<div class="line"><a name="l00204"></a><span class="lineno"> 204</span>  <span class="keywordflow">if</span> (fout.good())</div>
<div class="line"><a name="l00205"></a><span class="lineno"> 205</span>  {</div>
<div class="line"><a name="l00206"></a><span class="lineno"> 206</span>  result = <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a9f63b0b4e3de67b937bfa3022caf7348">saveResultsToStream</a>(fout);</div>
<div class="line"><a name="l00207"></a><span class="lineno"> 207</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Results saved to '%s'"</span>, filename);</div>
<div class="line"><a name="l00208"></a><span class="lineno"> 208</span>  }</div>
<div class="line"><a name="l00209"></a><span class="lineno"> 209</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00210"></a><span class="lineno"> 210</span>  {</div>
<div class="line"><a name="l00211"></a><span class="lineno"> 211</span>  <span class="comment">// try to save to a different file, if we can</span></div>
<div class="line"><a name="l00212"></a><span class="lineno"> 212</span>  <span class="keywordflow">if</span> (getResultsFilename(<a class="code" href="classompl_1_1tools_1_1Benchmark.html#a6a7267b64dbde28d9b505ffac55c217e">exp_</a>) != std::string(filename))</div>
<div class="line"><a name="l00213"></a><span class="lineno"> 213</span>  result = <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a979f5df0704b89e7da4a1c29ab857a02">saveResultsToFile</a>();</div>
<div class="line"><a name="l00214"></a><span class="lineno"> 214</span>  </div>
<div class="line"><a name="l00215"></a><span class="lineno"> 215</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Unable to write results to '%s'"</span>, filename);</div>
<div class="line"><a name="l00216"></a><span class="lineno"> 216</span>  }</div>
<div class="line"><a name="l00217"></a><span class="lineno"> 217</span>  <span class="keywordflow">return</span> result;</div>
<div class="line"><a name="l00218"></a><span class="lineno"> 218</span> }</div>
<div class="line"><a name="l00219"></a><span class="lineno"> 219</span>  </div>
<div class="line"><a name="l00220"></a><span class="lineno"><a class="line" href="classompl_1_1tools_1_1Benchmark.html#a979f5df0704b89e7da4a1c29ab857a02"> 220</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a979f5df0704b89e7da4a1c29ab857a02">ompl::tools::Benchmark::saveResultsToFile</a>()<span class="keyword"> const</span></div>
<div class="line"><a name="l00221"></a><span class="lineno"> 221</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00222"></a><span class="lineno"> 222</span>  std::string filename = getResultsFilename(exp_);</div>
<div class="line"><a name="l00223"></a><span class="lineno"> 223</span>  <span class="keywordflow">return</span> saveResultsToFile(filename.c_str());</div>
<div class="line"><a name="l00224"></a><span class="lineno"> 224</span> }</div>
<div class="line"><a name="l00225"></a><span class="lineno"> 225</span>  </div>
<div class="line"><a name="l00226"></a><span class="lineno"><a class="line" href="classompl_1_1tools_1_1Benchmark.html#a9f63b0b4e3de67b937bfa3022caf7348"> 226</a></span> <span class="keywordtype">bool</span> <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a9f63b0b4e3de67b937bfa3022caf7348">ompl::tools::Benchmark::saveResultsToStream</a>(std::ostream &out)<span class="keyword"> const</span></div>
<div class="line"><a name="l00227"></a><span class="lineno"> 227</span> <span class="keyword"></span>{</div>
<div class="line"><a name="l00228"></a><span class="lineno"> 228</span>  <span class="keywordflow">if</span> (exp_.planners.empty())</div>
<div class="line"><a name="l00229"></a><span class="lineno"> 229</span>  {</div>
<div class="line"><a name="l00230"></a><span class="lineno"> 230</span>  <a class="code" href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a>(<span class="stringliteral">"There is no experimental data to save"</span>);</div>
<div class="line"><a name="l00231"></a><span class="lineno"> 231</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00232"></a><span class="lineno"> 232</span>  }</div>
<div class="line"><a name="l00233"></a><span class="lineno"> 233</span>  </div>
<div class="line"><a name="l00234"></a><span class="lineno"> 234</span>  <span class="keywordflow">if</span> (!out.good())</div>
<div class="line"><a name="l00235"></a><span class="lineno"> 235</span>  {</div>
<div class="line"><a name="l00236"></a><span class="lineno"> 236</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"Unable to write to stream"</span>);</div>
<div class="line"><a name="l00237"></a><span class="lineno"> 237</span>  <span class="keywordflow">return</span> <span class="keyword">false</span>;</div>
<div class="line"><a name="l00238"></a><span class="lineno"> 238</span>  }</div>
<div class="line"><a name="l00239"></a><span class="lineno"> 239</span>  </div>
<div class="line"><a name="l00240"></a><span class="lineno"> 240</span>  out << <span class="stringliteral">"OMPL version "</span> << OMPL_VERSION << std::endl;</div>
<div class="line"><a name="l00241"></a><span class="lineno"> 241</span>  out << <span class="stringliteral">"Experiment "</span> << (exp_.name.empty() ? <span class="stringliteral">"NO_NAME"</span> : exp_.name) << std::endl;</div>
<div class="line"><a name="l00242"></a><span class="lineno"> 242</span>  </div>
<div class="line"><a name="l00243"></a><span class="lineno"> 243</span>  out << exp_.parameters.size() << <span class="stringliteral">" experiment properties"</span> << std::endl;</div>
<div class="line"><a name="l00244"></a><span class="lineno"> 244</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &parameter : exp_.parameters)</div>
<div class="line"><a name="l00245"></a><span class="lineno"> 245</span>  out << parameter.first << <span class="stringliteral">" = "</span> << parameter.second << std::endl;</div>
<div class="line"><a name="l00246"></a><span class="lineno"> 246</span>  </div>
<div class="line"><a name="l00247"></a><span class="lineno"> 247</span>  out << <span class="stringliteral">"Running on "</span> << (exp_.host.empty() ? <span class="stringliteral">"UNKNOWN"</span> : exp_.host) << std::endl;</div>
<div class="line"><a name="l00248"></a><span class="lineno"> 248</span>  out << <span class="stringliteral">"Starting at "</span> << <a class="code" href="namespaceompl_1_1time.html#ae8d794354a37128403aba90a187fe532">time::as_string</a>(exp_.startTime) << std::endl;</div>
<div class="line"><a name="l00249"></a><span class="lineno"> 249</span>  out << <span class="stringliteral">"<<<|"</span> << std::endl << exp_.setupInfo << <span class="stringliteral">"|>>>"</span> << std::endl;</div>
<div class="line"><a name="l00250"></a><span class="lineno"> 250</span>  out << <span class="stringliteral">"<<<|"</span> << std::endl << exp_.cpuInfo << <span class="stringliteral">"|>>>"</span> << std::endl;</div>
<div class="line"><a name="l00251"></a><span class="lineno"> 251</span>  </div>
<div class="line"><a name="l00252"></a><span class="lineno"> 252</span>  out << exp_.seed << <span class="stringliteral">" is the random seed"</span> << std::endl;</div>
<div class="line"><a name="l00253"></a><span class="lineno"> 253</span>  out << exp_.maxTime << <span class="stringliteral">" seconds per run"</span> << std::endl;</div>
<div class="line"><a name="l00254"></a><span class="lineno"> 254</span>  out << exp_.maxMem << <span class="stringliteral">" MB per run"</span> << std::endl;</div>
<div class="line"><a name="l00255"></a><span class="lineno"> 255</span>  out << exp_.runCount << <span class="stringliteral">" runs per planner"</span> << std::endl;</div>
<div class="line"><a name="l00256"></a><span class="lineno"> 256</span>  out << exp_.totalDuration << <span class="stringliteral">" seconds spent to collect the data"</span> << std::endl;</div>
<div class="line"><a name="l00257"></a><span class="lineno"> 257</span>  </div>
<div class="line"><a name="l00258"></a><span class="lineno"> 258</span>  <span class="comment">// change this if more enum types are added</span></div>
<div class="line"><a name="l00259"></a><span class="lineno"> 259</span>  out << <span class="stringliteral">"1 enum type"</span> << std::endl;</div>
<div class="line"><a name="l00260"></a><span class="lineno"> 260</span>  out << <span class="stringliteral">"status"</span>;</div>
<div class="line"><a name="l00261"></a><span class="lineno"> 261</span>  <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0; i < <a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4ac60ae0f04326edcd4fa202cda3dddb33">base::PlannerStatus::TYPE_COUNT</a>; ++i)</div>
<div class="line"><a name="l00262"></a><span class="lineno"> 262</span>  out << <span class="charliteral">'|'</span> << <a class="code" href="structompl_1_1base_1_1PlannerStatus.html">base::PlannerStatus</a>(<span class="keyword">static_cast<</span><a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">base::PlannerStatus::StatusType</a><span class="keyword">></span>(i)).<a class="code" href="structompl_1_1base_1_1PlannerStatus.html#ac9bdc9db7d5325710fb9ac74d27900ad">asString</a>();</div>
<div class="line"><a name="l00263"></a><span class="lineno"> 263</span>  out << std::endl;</div>
<div class="line"><a name="l00264"></a><span class="lineno"> 264</span>  </div>
<div class="line"><a name="l00265"></a><span class="lineno"> 265</span>  out << exp_.planners.size() << <span class="stringliteral">" planners"</span> << std::endl;</div>
<div class="line"><a name="l00266"></a><span class="lineno"> 266</span>  </div>
<div class="line"><a name="l00267"></a><span class="lineno"> 267</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &planner : exp_.planners)</div>
<div class="line"><a name="l00268"></a><span class="lineno"> 268</span>  {</div>
<div class="line"><a name="l00269"></a><span class="lineno"> 269</span>  out << planner.name << std::endl;</div>
<div class="line"><a name="l00270"></a><span class="lineno"> 270</span>  </div>
<div class="line"><a name="l00271"></a><span class="lineno"> 271</span>  <span class="comment">// get names of common properties</span></div>
<div class="line"><a name="l00272"></a><span class="lineno"> 272</span>  std::vector<std::string> properties;</div>
<div class="line"><a name="l00273"></a><span class="lineno"> 273</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &property : planner.common)</div>
<div class="line"><a name="l00274"></a><span class="lineno"> 274</span>  properties.push_back(property.first);</div>
<div class="line"><a name="l00275"></a><span class="lineno"> 275</span>  std::sort(properties.begin(), properties.end());</div>
<div class="line"><a name="l00276"></a><span class="lineno"> 276</span>  </div>
<div class="line"><a name="l00277"></a><span class="lineno"> 277</span>  <span class="comment">// print names & values of common properties</span></div>
<div class="line"><a name="l00278"></a><span class="lineno"> 278</span>  out << properties.size() << <span class="stringliteral">" common properties"</span> << std::endl;</div>
<div class="line"><a name="l00279"></a><span class="lineno"> 279</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &property : properties)</div>
<div class="line"><a name="l00280"></a><span class="lineno"> 280</span>  {</div>
<div class="line"><a name="l00281"></a><span class="lineno"> 281</span>  <span class="keyword">auto</span> it = planner.common.find(property);</div>
<div class="line"><a name="l00282"></a><span class="lineno"> 282</span>  out << it->first << <span class="stringliteral">" = "</span> << it->second << std::endl;</div>
<div class="line"><a name="l00283"></a><span class="lineno"> 283</span>  }</div>
<div class="line"><a name="l00284"></a><span class="lineno"> 284</span>  </div>
<div class="line"><a name="l00285"></a><span class="lineno"> 285</span>  <span class="comment">// construct the list of all possible properties for all runs</span></div>
<div class="line"><a name="l00286"></a><span class="lineno"> 286</span>  std::map<std::string, bool> propSeen;</div>
<div class="line"><a name="l00287"></a><span class="lineno"> 287</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &run : planner.runs)</div>
<div class="line"><a name="l00288"></a><span class="lineno"> 288</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &property : run)</div>
<div class="line"><a name="l00289"></a><span class="lineno"> 289</span>  propSeen[<span class="keyword">property</span>.first] = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00290"></a><span class="lineno"> 290</span>  </div>
<div class="line"><a name="l00291"></a><span class="lineno"> 291</span>  properties.clear();</div>
<div class="line"><a name="l00292"></a><span class="lineno"> 292</span>  </div>
<div class="line"><a name="l00293"></a><span class="lineno"> 293</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &it : propSeen)</div>
<div class="line"><a name="l00294"></a><span class="lineno"> 294</span>  properties.push_back(it.first);</div>
<div class="line"><a name="l00295"></a><span class="lineno"> 295</span>  std::sort(properties.begin(), properties.end());</div>
<div class="line"><a name="l00296"></a><span class="lineno"> 296</span>  </div>
<div class="line"><a name="l00297"></a><span class="lineno"> 297</span>  <span class="comment">// print the property names</span></div>
<div class="line"><a name="l00298"></a><span class="lineno"> 298</span>  out << properties.size() << <span class="stringliteral">" properties for each run"</span> << std::endl;</div>
<div class="line"><a name="l00299"></a><span class="lineno"> 299</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &property : properties)</div>
<div class="line"><a name="l00300"></a><span class="lineno"> 300</span>  out << <span class="keyword">property</span> << std::endl;</div>
<div class="line"><a name="l00301"></a><span class="lineno"> 301</span>  </div>
<div class="line"><a name="l00302"></a><span class="lineno"> 302</span>  <span class="comment">// print the data for each run</span></div>
<div class="line"><a name="l00303"></a><span class="lineno"> 303</span>  out << planner.runs.size() << <span class="stringliteral">" runs"</span> << std::endl;</div>
<div class="line"><a name="l00304"></a><span class="lineno"> 304</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &run : planner.runs)</div>
<div class="line"><a name="l00305"></a><span class="lineno"> 305</span>  {</div>
<div class="line"><a name="l00306"></a><span class="lineno"> 306</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &property : properties)</div>
<div class="line"><a name="l00307"></a><span class="lineno"> 307</span>  {</div>
<div class="line"><a name="l00308"></a><span class="lineno"> 308</span>  <span class="keyword">auto</span> it = run.find(property);</div>
<div class="line"><a name="l00309"></a><span class="lineno"> 309</span>  <span class="keywordflow">if</span> (it != run.end())</div>
<div class="line"><a name="l00310"></a><span class="lineno"> 310</span>  out << it->second;</div>
<div class="line"><a name="l00311"></a><span class="lineno"> 311</span>  out << <span class="stringliteral">"; "</span>;</div>
<div class="line"><a name="l00312"></a><span class="lineno"> 312</span>  }</div>
<div class="line"><a name="l00313"></a><span class="lineno"> 313</span>  out << std::endl;</div>
<div class="line"><a name="l00314"></a><span class="lineno"> 314</span>  }</div>
<div class="line"><a name="l00315"></a><span class="lineno"> 315</span>  </div>
<div class="line"><a name="l00316"></a><span class="lineno"> 316</span>  <span class="comment">// print the run progress data if it was reported</span></div>
<div class="line"><a name="l00317"></a><span class="lineno"> 317</span>  <span class="keywordflow">if</span> (planner.runsProgressData.size() > 0)</div>
<div class="line"><a name="l00318"></a><span class="lineno"> 318</span>  {</div>
<div class="line"><a name="l00319"></a><span class="lineno"> 319</span>  <span class="comment">// Print number of progress properties</span></div>
<div class="line"><a name="l00320"></a><span class="lineno"> 320</span>  out << planner.progressPropertyNames.size() << <span class="stringliteral">" progress properties for each run"</span> << std::endl;</div>
<div class="line"><a name="l00321"></a><span class="lineno"> 321</span>  <span class="comment">// Print progress property names</span></div>
<div class="line"><a name="l00322"></a><span class="lineno"> 322</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &progPropName : planner.progressPropertyNames)</div>
<div class="line"><a name="l00323"></a><span class="lineno"> 323</span>  {</div>
<div class="line"><a name="l00324"></a><span class="lineno"> 324</span>  out << progPropName << std::endl;</div>
<div class="line"><a name="l00325"></a><span class="lineno"> 325</span>  }</div>
<div class="line"><a name="l00326"></a><span class="lineno"> 326</span>  <span class="comment">// Print progress properties for each run</span></div>
<div class="line"><a name="l00327"></a><span class="lineno"> 327</span>  out << planner.runsProgressData.size() << <span class="stringliteral">" runs"</span> << std::endl;</div>
<div class="line"><a name="l00328"></a><span class="lineno"> 328</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &r : planner.runsProgressData)</div>
<div class="line"><a name="l00329"></a><span class="lineno"> 329</span>  {</div>
<div class="line"><a name="l00330"></a><span class="lineno"> 330</span>  <span class="comment">// For each time point</span></div>
<div class="line"><a name="l00331"></a><span class="lineno"> 331</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &t : r)</div>
<div class="line"><a name="l00332"></a><span class="lineno"> 332</span>  {</div>
<div class="line"><a name="l00333"></a><span class="lineno"> 333</span>  <span class="comment">// Print each of the properties at that time point</span></div>
<div class="line"><a name="l00334"></a><span class="lineno"> 334</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &iter : t)</div>
<div class="line"><a name="l00335"></a><span class="lineno"> 335</span>  {</div>
<div class="line"><a name="l00336"></a><span class="lineno"> 336</span>  out << iter.second << <span class="stringliteral">","</span>;</div>
<div class="line"><a name="l00337"></a><span class="lineno"> 337</span>  }</div>
<div class="line"><a name="l00338"></a><span class="lineno"> 338</span>  </div>
<div class="line"><a name="l00339"></a><span class="lineno"> 339</span>  <span class="comment">// Separate time points by semicolons</span></div>
<div class="line"><a name="l00340"></a><span class="lineno"> 340</span>  out << <span class="stringliteral">";"</span>;</div>
<div class="line"><a name="l00341"></a><span class="lineno"> 341</span>  }</div>
<div class="line"><a name="l00342"></a><span class="lineno"> 342</span>  </div>
<div class="line"><a name="l00343"></a><span class="lineno"> 343</span>  <span class="comment">// Separate runs by newlines</span></div>
<div class="line"><a name="l00344"></a><span class="lineno"> 344</span>  out << std::endl;</div>
<div class="line"><a name="l00345"></a><span class="lineno"> 345</span>  }</div>
<div class="line"><a name="l00346"></a><span class="lineno"> 346</span>  }</div>
<div class="line"><a name="l00347"></a><span class="lineno"> 347</span>  </div>
<div class="line"><a name="l00348"></a><span class="lineno"> 348</span>  out << <span class="charliteral">'.'</span> << std::endl;</div>
<div class="line"><a name="l00349"></a><span class="lineno"> 349</span>  }</div>
<div class="line"><a name="l00350"></a><span class="lineno"> 350</span>  <span class="keywordflow">return</span> <span class="keyword">true</span>;</div>
<div class="line"><a name="l00351"></a><span class="lineno"> 351</span> }</div>
<div class="line"><a name="l00352"></a><span class="lineno"> 352</span>  </div>
<div class="line"><a name="l00353"></a><span class="lineno"><a class="line" href="classompl_1_1tools_1_1Benchmark.html#a3257cb8dccc15037e81c0f235c61a7e8"> 353</a></span> <span class="keywordtype">void</span> <a class="code" href="classompl_1_1tools_1_1Benchmark.html#a3257cb8dccc15037e81c0f235c61a7e8">ompl::tools::Benchmark::benchmark</a>(<span class="keyword">const</span> <a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html">Request</a> &req)</div>
<div class="line"><a name="l00354"></a><span class="lineno"> 354</span> {</div>
<div class="line"><a name="l00355"></a><span class="lineno"> 355</span>  <span class="comment">// sanity checks</span></div>
<div class="line"><a name="l00356"></a><span class="lineno"> 356</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00357"></a><span class="lineno"> 357</span>  {</div>
<div class="line"><a name="l00358"></a><span class="lineno"> 358</span>  <span class="keywordflow">if</span> (!gsetup_->getSpaceInformation()->isSetup())</div>
<div class="line"><a name="l00359"></a><span class="lineno"> 359</span>  gsetup_->getSpaceInformation()->setup();</div>
<div class="line"><a name="l00360"></a><span class="lineno"> 360</span>  }</div>
<div class="line"><a name="l00361"></a><span class="lineno"> 361</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00362"></a><span class="lineno"> 362</span>  {</div>
<div class="line"><a name="l00363"></a><span class="lineno"> 363</span>  <span class="keywordflow">if</span> (!csetup_->getSpaceInformation()->isSetup())</div>
<div class="line"><a name="l00364"></a><span class="lineno"> 364</span>  csetup_->getSpaceInformation()->setup();</div>
<div class="line"><a name="l00365"></a><span class="lineno"> 365</span>  }</div>
<div class="line"><a name="l00366"></a><span class="lineno"> 366</span>  </div>
<div class="line"><a name="l00367"></a><span class="lineno"> 367</span>  <span class="keywordflow">if</span> (!(gsetup_ ? gsetup_->getGoal() : csetup_->getGoal()))</div>
<div class="line"><a name="l00368"></a><span class="lineno"> 368</span>  {</div>
<div class="line"><a name="l00369"></a><span class="lineno"> 369</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"No goal defined"</span>);</div>
<div class="line"><a name="l00370"></a><span class="lineno"> 370</span>  <span class="keywordflow">return</span>;</div>
<div class="line"><a name="l00371"></a><span class="lineno"> 371</span>  }</div>
<div class="line"><a name="l00372"></a><span class="lineno"> 372</span>  </div>
<div class="line"><a name="l00373"></a><span class="lineno"> 373</span>  <span class="keywordflow">if</span> (planners_.empty())</div>
<div class="line"><a name="l00374"></a><span class="lineno"> 374</span>  {</div>
<div class="line"><a name="l00375"></a><span class="lineno"> 375</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(<span class="stringliteral">"There are no planners to benchmark"</span>);</div>
<div class="line"><a name="l00376"></a><span class="lineno"> 376</span>  <span class="keywordflow">return</span>;</div>
<div class="line"><a name="l00377"></a><span class="lineno"> 377</span>  }</div>
<div class="line"><a name="l00378"></a><span class="lineno"> 378</span>  </div>
<div class="line"><a name="l00379"></a><span class="lineno"> 379</span>  status_.running = <span class="keyword">true</span>;</div>
<div class="line"><a name="l00380"></a><span class="lineno"> 380</span>  exp_.totalDuration = 0.0;</div>
<div class="line"><a name="l00381"></a><span class="lineno"> 381</span>  exp_.maxTime = req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#ae29e119a2a3ca7d1325f701159a7636a">maxTime</a>;</div>
<div class="line"><a name="l00382"></a><span class="lineno"> 382</span>  exp_.maxMem = req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a12b3d959f8e7349120cdd87ef21f72b8">maxMem</a>;</div>
<div class="line"><a name="l00383"></a><span class="lineno"> 383</span>  exp_.runCount = req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a>;</div>
<div class="line"><a name="l00384"></a><span class="lineno"> 384</span>  exp_.host = <a class="code" href="namespaceompl_1_1machine.html#a72f733ca0ea9660e62e7d78887778494">machine::getHostname</a>();</div>
<div class="line"><a name="l00385"></a><span class="lineno"> 385</span>  exp_.cpuInfo = <a class="code" href="namespaceompl_1_1machine.html#a75c4da4e42a1de9050a171213135fa26">machine::getCPUInfo</a>();</div>
<div class="line"><a name="l00386"></a><span class="lineno"> 386</span>  exp_.seed = <a class="code" href="classompl_1_1RNG.html#a9b59291cc9599888d41a1b7a748aa5fe">RNG::getSeed</a>();</div>
<div class="line"><a name="l00387"></a><span class="lineno"> 387</span>  </div>
<div class="line"><a name="l00388"></a><span class="lineno"> 388</span>  exp_.startTime = <a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>();</div>
<div class="line"><a name="l00389"></a><span class="lineno"> 389</span>  </div>
<div class="line"><a name="l00390"></a><span class="lineno"> 390</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Configuring planners ..."</span>);</div>
<div class="line"><a name="l00391"></a><span class="lineno"> 391</span>  </div>
<div class="line"><a name="l00392"></a><span class="lineno"> 392</span>  <span class="comment">// clear previous experimental data</span></div>
<div class="line"><a name="l00393"></a><span class="lineno"> 393</span>  exp_.planners.clear();</div>
<div class="line"><a name="l00394"></a><span class="lineno"> 394</span>  exp_.planners.resize(planners_.size());</div>
<div class="line"><a name="l00395"></a><span class="lineno"> 395</span>  </div>
<div class="line"><a name="l00396"></a><span class="lineno"> 396</span>  <span class="keyword">const</span> base::ProblemDefinitionPtr &pdef =</div>
<div class="line"><a name="l00397"></a><span class="lineno"> 397</span>  gsetup_ ? gsetup_->getProblemDefinition() : csetup_->getProblemDefinition();</div>
<div class="line"><a name="l00398"></a><span class="lineno"> 398</span>  <span class="comment">// set up all the planners</span></div>
<div class="line"><a name="l00399"></a><span class="lineno"> 399</span>  <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0; i < planners_.size(); ++i)</div>
<div class="line"><a name="l00400"></a><span class="lineno"> 400</span>  {</div>
<div class="line"><a name="l00401"></a><span class="lineno"> 401</span>  <span class="comment">// configure the planner</span></div>
<div class="line"><a name="l00402"></a><span class="lineno"> 402</span>  planners_[i]->setProblemDefinition(pdef);</div>
<div class="line"><a name="l00403"></a><span class="lineno"> 403</span>  <span class="keywordflow">if</span> (!planners_[i]->isSetup())</div>
<div class="line"><a name="l00404"></a><span class="lineno"> 404</span>  planners_[i]->setup();</div>
<div class="line"><a name="l00405"></a><span class="lineno"> 405</span>  exp_.planners[i].name = (gsetup_ ? <span class="stringliteral">"geometric_"</span> : <span class="stringliteral">"control_"</span>) + planners_[i]->getName();</div>
<div class="line"><a name="l00406"></a><span class="lineno"> 406</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Configured %s"</span>, exp_.planners[i].name.c_str());</div>
<div class="line"><a name="l00407"></a><span class="lineno"> 407</span>  }</div>
<div class="line"><a name="l00408"></a><span class="lineno"> 408</span>  </div>
<div class="line"><a name="l00409"></a><span class="lineno"> 409</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Done configuring planners."</span>);</div>
<div class="line"><a name="l00410"></a><span class="lineno"> 410</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Saving planner setup information ..."</span>);</div>
<div class="line"><a name="l00411"></a><span class="lineno"> 411</span>  </div>
<div class="line"><a name="l00412"></a><span class="lineno"> 412</span>  std::stringstream setupInfo;</div>
<div class="line"><a name="l00413"></a><span class="lineno"> 413</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00414"></a><span class="lineno"> 414</span>  gsetup_->print(setupInfo);</div>
<div class="line"><a name="l00415"></a><span class="lineno"> 415</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00416"></a><span class="lineno"> 416</span>  csetup_->print(setupInfo);</div>
<div class="line"><a name="l00417"></a><span class="lineno"> 417</span>  setupInfo << std::endl << <span class="stringliteral">"Properties of benchmarked planners:"</span> << std::endl;</div>
<div class="line"><a name="l00418"></a><span class="lineno"> 418</span>  <span class="keywordflow">for</span> (<span class="keyword">auto</span> &planner : planners_)</div>
<div class="line"><a name="l00419"></a><span class="lineno"> 419</span>  planner->printProperties(setupInfo);</div>
<div class="line"><a name="l00420"></a><span class="lineno"> 420</span>  </div>
<div class="line"><a name="l00421"></a><span class="lineno"> 421</span>  exp_.setupInfo = setupInfo.str();</div>
<div class="line"><a name="l00422"></a><span class="lineno"> 422</span>  </div>
<div class="line"><a name="l00423"></a><span class="lineno"> 423</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Done saving information"</span>);</div>
<div class="line"><a name="l00424"></a><span class="lineno"> 424</span>  </div>
<div class="line"><a name="l00425"></a><span class="lineno"> 425</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Beginning benchmark"</span>);</div>
<div class="line"><a name="l00426"></a><span class="lineno"> 426</span>  <a class="code" href="classompl_1_1msg_1_1OutputHandler.html">msg::OutputHandler</a> *oh = <a class="code" href="namespaceompl_1_1msg.html#a0e9a5d161592281f8caf01b0c8b2e746">msg::getOutputHandler</a>();</div>
<div class="line"><a name="l00427"></a><span class="lineno"> 427</span>  boost::scoped_ptr<msg::OutputHandlerFile> ohf;</div>
<div class="line"><a name="l00428"></a><span class="lineno"> 428</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a882d384685f86176fbb441c256d34044">saveConsoleOutput</a>)</div>
<div class="line"><a name="l00429"></a><span class="lineno"> 429</span>  {</div>
<div class="line"><a name="l00430"></a><span class="lineno"> 430</span>  ohf.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1msg_1_1OutputHandlerFile.html">msg::OutputHandlerFile</a>(getConsoleFilename(exp_).c_str()));</div>
<div class="line"><a name="l00431"></a><span class="lineno"> 431</span>  <a class="code" href="namespaceompl_1_1msg.html#a66fd8fd39855d4166ff40164fe4d9d6b">msg::useOutputHandler</a>(ohf.get());</div>
<div class="line"><a name="l00432"></a><span class="lineno"> 432</span>  }</div>
<div class="line"><a name="l00433"></a><span class="lineno"> 433</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00434"></a><span class="lineno"> 434</span>  <a class="code" href="namespaceompl_1_1msg.html#a83e28f524a5576a73bb062523bbdc53d">msg::noOutputHandler</a>();</div>
<div class="line"><a name="l00435"></a><span class="lineno"> 435</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Beginning benchmark"</span>);</div>
<div class="line"><a name="l00436"></a><span class="lineno"> 436</span>  </div>
<div class="line"><a name="l00437"></a><span class="lineno"> 437</span>  boost::scoped_ptr<ompl::time::ProgressDisplay> progress;</div>
<div class="line"><a name="l00438"></a><span class="lineno"> 438</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0e63ef873358346cfb78a69121dfd2ec">displayProgress</a>)</div>
<div class="line"><a name="l00439"></a><span class="lineno"> 439</span>  {</div>
<div class="line"><a name="l00440"></a><span class="lineno"> 440</span>  std::cout << <span class="stringliteral">"Running experiment "</span> << exp_.name << <span class="stringliteral">"."</span> << std::endl;</div>
<div class="line"><a name="l00441"></a><span class="lineno"> 441</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a>)</div>
<div class="line"><a name="l00442"></a><span class="lineno"> 442</span>  std::cout << <span class="stringliteral">"Each planner will be executed "</span> << req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a> << <span class="stringliteral">" times for at most "</span> << req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#ae29e119a2a3ca7d1325f701159a7636a">maxTime</a> << <span class="stringliteral">" seconds."</span>;</div>
<div class="line"><a name="l00443"></a><span class="lineno"> 443</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00444"></a><span class="lineno"> 444</span>  std::cout << <span class="stringliteral">"Each planner will be executed as many times as possible within "</span> << req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#ae29e119a2a3ca7d1325f701159a7636a">maxTime</a> << <span class="stringliteral">" seconds."</span>;</div>
<div class="line"><a name="l00445"></a><span class="lineno"> 445</span>  std::cout << <span class="stringliteral">" Memory is limited at "</span> << req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a12b3d959f8e7349120cdd87ef21f72b8">maxMem</a> << <span class="stringliteral">"MB."</span> << std::endl;</div>
<div class="line"><a name="l00446"></a><span class="lineno"> 446</span>  progress.reset(<span class="keyword">new</span> <a class="code" href="classompl_1_1time_1_1ProgressDisplay.html">ompl::time::ProgressDisplay</a>);</div>
<div class="line"><a name="l00447"></a><span class="lineno"> 447</span>  }</div>
<div class="line"><a name="l00448"></a><span class="lineno"> 448</span>  </div>
<div class="line"><a name="l00449"></a><span class="lineno"> 449</span>  <a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a> memStart = <a class="code" href="namespaceompl_1_1machine.html#a263d0e9d43cd9e10edb468b97f46a198">machine::getProcessMemoryUsage</a>();</div>
<div class="line"><a name="l00450"></a><span class="lineno"> 450</span>  <span class="keyword">auto</span> maxMemBytes = (<a class="code" href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">machine::MemUsage_t</a>)(req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a12b3d959f8e7349120cdd87ef21f72b8">maxMem</a> * 1024 * 1024);</div>
<div class="line"><a name="l00451"></a><span class="lineno"> 451</span>  </div>
<div class="line"><a name="l00452"></a><span class="lineno"> 452</span>  <span class="keywordflow">for</span> (<span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> i = 0; i < planners_.size(); ++i)</div>
<div class="line"><a name="l00453"></a><span class="lineno"> 453</span>  {</div>
<div class="line"><a name="l00454"></a><span class="lineno"> 454</span>  status_.activePlanner = exp_.planners[i].name;</div>
<div class="line"><a name="l00455"></a><span class="lineno"> 455</span>  <span class="comment">// execute planner switch event, if set</span></div>
<div class="line"><a name="l00456"></a><span class="lineno"> 456</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00457"></a><span class="lineno"> 457</span>  {</div>
<div class="line"><a name="l00458"></a><span class="lineno"> 458</span>  <span class="keywordflow">if</span> (plannerSwitch_)</div>
<div class="line"><a name="l00459"></a><span class="lineno"> 459</span>  {</div>
<div class="line"><a name="l00460"></a><span class="lineno"> 460</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Executing planner-switch event for planner %s ..."</span>, status_.activePlanner.c_str());</div>
<div class="line"><a name="l00461"></a><span class="lineno"> 461</span>  plannerSwitch_(planners_[i]);</div>
<div class="line"><a name="l00462"></a><span class="lineno"> 462</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Completed execution of planner-switch event"</span>);</div>
<div class="line"><a name="l00463"></a><span class="lineno"> 463</span>  }</div>
<div class="line"><a name="l00464"></a><span class="lineno"> 464</span>  }</div>
<div class="line"><a name="l00465"></a><span class="lineno"> 465</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00466"></a><span class="lineno"> 466</span>  {</div>
<div class="line"><a name="l00467"></a><span class="lineno"> 467</span>  std::stringstream es;</div>
<div class="line"><a name="l00468"></a><span class="lineno"> 468</span>  es << <span class="stringliteral">"There was an error executing the planner-switch event for planner "</span> << status_.activePlanner</div>
<div class="line"><a name="l00469"></a><span class="lineno"> 469</span>  << std::endl;</div>
<div class="line"><a name="l00470"></a><span class="lineno"> 470</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00471"></a><span class="lineno"> 471</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00472"></a><span class="lineno"> 472</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00473"></a><span class="lineno"> 473</span>  }</div>
<div class="line"><a name="l00474"></a><span class="lineno"> 474</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00475"></a><span class="lineno"> 475</span>  gsetup_->setup();</div>
<div class="line"><a name="l00476"></a><span class="lineno"> 476</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00477"></a><span class="lineno"> 477</span>  csetup_->setup();</div>
<div class="line"><a name="l00478"></a><span class="lineno"> 478</span>  planners_[i]->params().getParams(exp_.planners[i].common);</div>
<div class="line"><a name="l00479"></a><span class="lineno"> 479</span>  planners_[i]->getSpaceInformation()->params().getParams(exp_.planners[i].common);</div>
<div class="line"><a name="l00480"></a><span class="lineno"> 480</span>  </div>
<div class="line"><a name="l00481"></a><span class="lineno"> 481</span>  <span class="comment">// Add planner progress property names to struct</span></div>
<div class="line"><a name="l00482"></a><span class="lineno"> 482</span>  exp_.planners[i].progressPropertyNames.emplace_back(<span class="stringliteral">"time REAL"</span>);</div>
<div class="line"><a name="l00483"></a><span class="lineno"> 483</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &property : planners_[i]->getPlannerProgressProperties())</div>
<div class="line"><a name="l00484"></a><span class="lineno"> 484</span>  {</div>
<div class="line"><a name="l00485"></a><span class="lineno"> 485</span>  exp_.planners[i].progressPropertyNames.push_back(property.first);</div>
<div class="line"><a name="l00486"></a><span class="lineno"> 486</span>  }</div>
<div class="line"><a name="l00487"></a><span class="lineno"> 487</span>  std::sort(exp_.planners[i].progressPropertyNames.begin(), exp_.planners[i].progressPropertyNames.end());</div>
<div class="line"><a name="l00488"></a><span class="lineno"> 488</span>  </div>
<div class="line"><a name="l00489"></a><span class="lineno"> 489</span>  <span class="comment">// run the planner</span></div>
<div class="line"><a name="l00490"></a><span class="lineno"> 490</span>  <span class="keywordtype">double</span> maxTime = req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#ae29e119a2a3ca7d1325f701159a7636a">maxTime</a>;</div>
<div class="line"><a name="l00491"></a><span class="lineno"> 491</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> j = 0;</div>
<div class="line"><a name="l00492"></a><span class="lineno"> 492</span>  <span class="keywordflow">while</span> (<span class="keyword">true</span>)</div>
<div class="line"><a name="l00493"></a><span class="lineno"> 493</span>  {</div>
<div class="line"><a name="l00494"></a><span class="lineno"> 494</span>  status_.activeRun = j;</div>
<div class="line"><a name="l00495"></a><span class="lineno"> 495</span>  status_.progressPercentage = req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a> ?</div>
<div class="line"><a name="l00496"></a><span class="lineno"> 496</span>  (double)(100 * (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a> * i + j)) / (<span class="keywordtype">double</span>)(planners_.size() * req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a>) :</div>
<div class="line"><a name="l00497"></a><span class="lineno"> 497</span>  (<span class="keywordtype">double</span>)(100 * i) / (<span class="keywordtype">double</span>)(planners_.size());</div>
<div class="line"><a name="l00498"></a><span class="lineno"> 498</span>  </div>
<div class="line"><a name="l00499"></a><span class="lineno"> 499</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0e63ef873358346cfb78a69121dfd2ec">displayProgress</a>)</div>
<div class="line"><a name="l00500"></a><span class="lineno"> 500</span>  <span class="keywordflow">while</span> (status_.progressPercentage > progress->count())</div>
<div class="line"><a name="l00501"></a><span class="lineno"> 501</span>  ++(*progress);</div>
<div class="line"><a name="l00502"></a><span class="lineno"> 502</span>  </div>
<div class="line"><a name="l00503"></a><span class="lineno"> 503</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Preparing for run %d of %s"</span>, status_.activeRun, status_.activePlanner.c_str());</div>
<div class="line"><a name="l00504"></a><span class="lineno"> 504</span>  </div>
<div class="line"><a name="l00505"></a><span class="lineno"> 505</span>  <span class="comment">// make sure all planning data structures are cleared</span></div>
<div class="line"><a name="l00506"></a><span class="lineno"> 506</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00507"></a><span class="lineno"> 507</span>  {</div>
<div class="line"><a name="l00508"></a><span class="lineno"> 508</span>  planners_[i]->clear();</div>
<div class="line"><a name="l00509"></a><span class="lineno"> 509</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00510"></a><span class="lineno"> 510</span>  {</div>
<div class="line"><a name="l00511"></a><span class="lineno"> 511</span>  gsetup_->getProblemDefinition()->clearSolutionPaths();</div>
<div class="line"><a name="l00512"></a><span class="lineno"> 512</span>  gsetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();</div>
<div class="line"><a name="l00513"></a><span class="lineno"> 513</span>  }</div>
<div class="line"><a name="l00514"></a><span class="lineno"> 514</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00515"></a><span class="lineno"> 515</span>  {</div>
<div class="line"><a name="l00516"></a><span class="lineno"> 516</span>  csetup_->getProblemDefinition()->clearSolutionPaths();</div>
<div class="line"><a name="l00517"></a><span class="lineno"> 517</span>  csetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();</div>
<div class="line"><a name="l00518"></a><span class="lineno"> 518</span>  }</div>
<div class="line"><a name="l00519"></a><span class="lineno"> 519</span>  }</div>
<div class="line"><a name="l00520"></a><span class="lineno"> 520</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00521"></a><span class="lineno"> 521</span>  {</div>
<div class="line"><a name="l00522"></a><span class="lineno"> 522</span>  std::stringstream es;</div>
<div class="line"><a name="l00523"></a><span class="lineno"> 523</span>  es << <span class="stringliteral">"There was an error while preparing for run "</span> << status_.activeRun << <span class="stringliteral">" of planner "</span></div>
<div class="line"><a name="l00524"></a><span class="lineno"> 524</span>  << status_.activePlanner << std::endl;</div>
<div class="line"><a name="l00525"></a><span class="lineno"> 525</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00526"></a><span class="lineno"> 526</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00527"></a><span class="lineno"> 527</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00528"></a><span class="lineno"> 528</span>  }</div>
<div class="line"><a name="l00529"></a><span class="lineno"> 529</span>  </div>
<div class="line"><a name="l00530"></a><span class="lineno"> 530</span>  <span class="comment">// execute pre-run event, if set</span></div>
<div class="line"><a name="l00531"></a><span class="lineno"> 531</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00532"></a><span class="lineno"> 532</span>  {</div>
<div class="line"><a name="l00533"></a><span class="lineno"> 533</span>  <span class="keywordflow">if</span> (preRun_)</div>
<div class="line"><a name="l00534"></a><span class="lineno"> 534</span>  {</div>
<div class="line"><a name="l00535"></a><span class="lineno"> 535</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Executing pre-run event for run %d of planner %s ..."</span>, status_.activeRun,</div>
<div class="line"><a name="l00536"></a><span class="lineno"> 536</span>  status_.activePlanner.c_str());</div>
<div class="line"><a name="l00537"></a><span class="lineno"> 537</span>  preRun_(planners_[i]);</div>
<div class="line"><a name="l00538"></a><span class="lineno"> 538</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Completed execution of pre-run event"</span>);</div>
<div class="line"><a name="l00539"></a><span class="lineno"> 539</span>  }</div>
<div class="line"><a name="l00540"></a><span class="lineno"> 540</span>  }</div>
<div class="line"><a name="l00541"></a><span class="lineno"> 541</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00542"></a><span class="lineno"> 542</span>  {</div>
<div class="line"><a name="l00543"></a><span class="lineno"> 543</span>  std::stringstream es;</div>
<div class="line"><a name="l00544"></a><span class="lineno"> 544</span>  es << <span class="stringliteral">"There was an error executing the pre-run event for run "</span> << status_.activeRun << <span class="stringliteral">" of planner "</span></div>
<div class="line"><a name="l00545"></a><span class="lineno"> 545</span>  << status_.activePlanner << std::endl;</div>
<div class="line"><a name="l00546"></a><span class="lineno"> 546</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00547"></a><span class="lineno"> 547</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00548"></a><span class="lineno"> 548</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00549"></a><span class="lineno"> 549</span>  }</div>
<div class="line"><a name="l00550"></a><span class="lineno"> 550</span>  </div>
<div class="line"><a name="l00551"></a><span class="lineno"> 551</span>  RunPlanner rp(<span class="keyword">this</span>);</div>
<div class="line"><a name="l00552"></a><span class="lineno"> 552</span>  rp.run(planners_[i], memStart, maxMemBytes, maxTime, req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a7f308d71127840e12c6fedfe2668d652">timeBetweenUpdates</a>);</div>
<div class="line"><a name="l00553"></a><span class="lineno"> 553</span>  <span class="keywordtype">bool</span> solved = gsetup_ ? gsetup_->haveSolutionPath() : csetup_->haveSolutionPath();</div>
<div class="line"><a name="l00554"></a><span class="lineno"> 554</span>  </div>
<div class="line"><a name="l00555"></a><span class="lineno"> 555</span>  <span class="comment">// store results</span></div>
<div class="line"><a name="l00556"></a><span class="lineno"> 556</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00557"></a><span class="lineno"> 557</span>  {</div>
<div class="line"><a name="l00558"></a><span class="lineno"> 558</span>  <a class="code" href="classompl_1_1tools_1_1Benchmark.html#ad660e80e710f6fd524d865bc232311e5">RunProperties</a> run;</div>
<div class="line"><a name="l00559"></a><span class="lineno"> 559</span>  </div>
<div class="line"><a name="l00560"></a><span class="lineno"> 560</span>  run[<span class="stringliteral">"time REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(rp.getTimeUsed());</div>
<div class="line"><a name="l00561"></a><span class="lineno"> 561</span>  run[<span class="stringliteral">"memory REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>((<span class="keywordtype">double</span>)rp.getMemUsed() / (1024.0 * 1024.0));</div>
<div class="line"><a name="l00562"></a><span class="lineno"> 562</span>  run[<span class="stringliteral">"status ENUM"</span>] = std::to_string((<span class="keywordtype">int</span>)<span class="keyword">static_cast<</span><a class="code" href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">base::PlannerStatus::StatusType</a><span class="keyword">></span>(rp.getStatus()));</div>
<div class="line"><a name="l00563"></a><span class="lineno"> 563</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00564"></a><span class="lineno"> 564</span>  {</div>
<div class="line"><a name="l00565"></a><span class="lineno"> 565</span>  run[<span class="stringliteral">"solved BOOLEAN"</span>] = std::to_string(gsetup_->haveExactSolutionPath());</div>
<div class="line"><a name="l00566"></a><span class="lineno"> 566</span>  run[<span class="stringliteral">"valid segment fraction REAL"</span>] =</div>
<div class="line"><a name="l00567"></a><span class="lineno"> 567</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());</div>
<div class="line"><a name="l00568"></a><span class="lineno"> 568</span>  }</div>
<div class="line"><a name="l00569"></a><span class="lineno"> 569</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00570"></a><span class="lineno"> 570</span>  {</div>
<div class="line"><a name="l00571"></a><span class="lineno"> 571</span>  run[<span class="stringliteral">"solved BOOLEAN"</span>] = std::to_string(csetup_->haveExactSolutionPath());</div>
<div class="line"><a name="l00572"></a><span class="lineno"> 572</span>  run[<span class="stringliteral">"valid segment fraction REAL"</span>] =</div>
<div class="line"><a name="l00573"></a><span class="lineno"> 573</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(csetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());</div>
<div class="line"><a name="l00574"></a><span class="lineno"> 574</span>  }</div>
<div class="line"><a name="l00575"></a><span class="lineno"> 575</span>  </div>
<div class="line"><a name="l00576"></a><span class="lineno"> 576</span>  <span class="keywordflow">if</span> (solved)</div>
<div class="line"><a name="l00577"></a><span class="lineno"> 577</span>  {</div>
<div class="line"><a name="l00578"></a><span class="lineno"> 578</span>  <span class="keywordflow">if</span> (gsetup_)</div>
<div class="line"><a name="l00579"></a><span class="lineno"> 579</span>  {</div>
<div class="line"><a name="l00580"></a><span class="lineno"> 580</span>  run[<span class="stringliteral">"approximate solution BOOLEAN"</span>] =</div>
<div class="line"><a name="l00581"></a><span class="lineno"> 581</span>  std::to_string(gsetup_->getProblemDefinition()->hasApproximateSolution());</div>
<div class="line"><a name="l00582"></a><span class="lineno"> 582</span>  run[<span class="stringliteral">"solution difference REAL"</span>] =</div>
<div class="line"><a name="l00583"></a><span class="lineno"> 583</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getProblemDefinition()->getSolutionDifference());</div>
<div class="line"><a name="l00584"></a><span class="lineno"> 584</span>  run[<span class="stringliteral">"solution length REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().length());</div>
<div class="line"><a name="l00585"></a><span class="lineno"> 585</span>  run[<span class="stringliteral">"solution smoothness REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().smoothness());</div>
<div class="line"><a name="l00586"></a><span class="lineno"> 586</span>  run[<span class="stringliteral">"solution clearance REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().clearance());</div>
<div class="line"><a name="l00587"></a><span class="lineno"> 587</span>  run[<span class="stringliteral">"solution segments INTEGER"</span>] =</div>
<div class="line"><a name="l00588"></a><span class="lineno"> 588</span>  std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);</div>
<div class="line"><a name="l00589"></a><span class="lineno"> 589</span>  run[<span class="stringliteral">"correct solution BOOLEAN"</span>] = std::to_string(gsetup_->getSolutionPath().check());</div>
<div class="line"><a name="l00590"></a><span class="lineno"> 590</span>  </div>
<div class="line"><a name="l00591"></a><span class="lineno"> 591</span>  <span class="keywordtype">unsigned</span> <span class="keywordtype">int</span> factor = gsetup_->getStateSpace()->getValidSegmentCountFactor();</div>
<div class="line"><a name="l00592"></a><span class="lineno"> 592</span>  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);</div>
<div class="line"><a name="l00593"></a><span class="lineno"> 593</span>  run[<span class="stringliteral">"correct solution strict BOOLEAN"</span>] = std::to_string(gsetup_->getSolutionPath().check());</div>
<div class="line"><a name="l00594"></a><span class="lineno"> 594</span>  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);</div>
<div class="line"><a name="l00595"></a><span class="lineno"> 595</span>  </div>
<div class="line"><a name="l00596"></a><span class="lineno"> 596</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#af7c98e06da0e8b8181a5feec8b57ac6d">simplify</a>)</div>
<div class="line"><a name="l00597"></a><span class="lineno"> 597</span>  {</div>
<div class="line"><a name="l00598"></a><span class="lineno"> 598</span>  <span class="comment">// simplify solution</span></div>
<div class="line"><a name="l00599"></a><span class="lineno"> 599</span>  <a class="code" href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">time::point</a> timeStart = <a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>();</div>
<div class="line"><a name="l00600"></a><span class="lineno"> 600</span>  gsetup_->simplifySolution();</div>
<div class="line"><a name="l00601"></a><span class="lineno"> 601</span>  <span class="keywordtype">double</span> timeUsed = <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(<a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() - timeStart);</div>
<div class="line"><a name="l00602"></a><span class="lineno"> 602</span>  run[<span class="stringliteral">"simplification time REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(timeUsed);</div>
<div class="line"><a name="l00603"></a><span class="lineno"> 603</span>  run[<span class="stringliteral">"simplified solution length REAL"</span>] =</div>
<div class="line"><a name="l00604"></a><span class="lineno"> 604</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().length());</div>
<div class="line"><a name="l00605"></a><span class="lineno"> 605</span>  run[<span class="stringliteral">"simplified solution smoothness REAL"</span>] =</div>
<div class="line"><a name="l00606"></a><span class="lineno"> 606</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().smoothness());</div>
<div class="line"><a name="l00607"></a><span class="lineno"> 607</span>  run[<span class="stringliteral">"simplified solution clearance REAL"</span>] =</div>
<div class="line"><a name="l00608"></a><span class="lineno"> 608</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(gsetup_->getSolutionPath().clearance());</div>
<div class="line"><a name="l00609"></a><span class="lineno"> 609</span>  run[<span class="stringliteral">"simplified solution segments INTEGER"</span>] =</div>
<div class="line"><a name="l00610"></a><span class="lineno"> 610</span>  std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);</div>
<div class="line"><a name="l00611"></a><span class="lineno"> 611</span>  run[<span class="stringliteral">"simplified correct solution BOOLEAN"</span>] =</div>
<div class="line"><a name="l00612"></a><span class="lineno"> 612</span>  std::to_string(gsetup_->getSolutionPath().check());</div>
<div class="line"><a name="l00613"></a><span class="lineno"> 613</span>  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);</div>
<div class="line"><a name="l00614"></a><span class="lineno"> 614</span>  run[<span class="stringliteral">"simplified correct solution strict BOOLEAN"</span>] =</div>
<div class="line"><a name="l00615"></a><span class="lineno"> 615</span>  std::to_string(gsetup_->getSolutionPath().check());</div>
<div class="line"><a name="l00616"></a><span class="lineno"> 616</span>  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);</div>
<div class="line"><a name="l00617"></a><span class="lineno"> 617</span>  }</div>
<div class="line"><a name="l00618"></a><span class="lineno"> 618</span>  }</div>
<div class="line"><a name="l00619"></a><span class="lineno"> 619</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00620"></a><span class="lineno"> 620</span>  {</div>
<div class="line"><a name="l00621"></a><span class="lineno"> 621</span>  run[<span class="stringliteral">"approximate solution BOOLEAN"</span>] =</div>
<div class="line"><a name="l00622"></a><span class="lineno"> 622</span>  std::to_string(csetup_->getProblemDefinition()->hasApproximateSolution());</div>
<div class="line"><a name="l00623"></a><span class="lineno"> 623</span>  run[<span class="stringliteral">"solution difference REAL"</span>] =</div>
<div class="line"><a name="l00624"></a><span class="lineno"> 624</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(csetup_->getProblemDefinition()->getSolutionDifference());</div>
<div class="line"><a name="l00625"></a><span class="lineno"> 625</span>  run[<span class="stringliteral">"solution length REAL"</span>] = <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(csetup_->getSolutionPath().length());</div>
<div class="line"><a name="l00626"></a><span class="lineno"> 626</span>  run[<span class="stringliteral">"solution clearance REAL"</span>] =</div>
<div class="line"><a name="l00627"></a><span class="lineno"> 627</span>  <a class="code" href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a>(csetup_->getSolutionPath().asGeometric().clearance());</div>
<div class="line"><a name="l00628"></a><span class="lineno"> 628</span>  run[<span class="stringliteral">"solution segments INTEGER"</span>] = std::to_string(csetup_->getSolutionPath().getControlCount());</div>
<div class="line"><a name="l00629"></a><span class="lineno"> 629</span>  run[<span class="stringliteral">"correct solution BOOLEAN"</span>] = std::to_string(csetup_->getSolutionPath().check());</div>
<div class="line"><a name="l00630"></a><span class="lineno"> 630</span>  }</div>
<div class="line"><a name="l00631"></a><span class="lineno"> 631</span>  }</div>
<div class="line"><a name="l00632"></a><span class="lineno"> 632</span>  </div>
<div class="line"><a name="l00633"></a><span class="lineno"> 633</span>  <a class="code" href="classompl_1_1base_1_1PlannerData.html">base::PlannerData</a> pd(gsetup_ ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation());</div>
<div class="line"><a name="l00634"></a><span class="lineno"> 634</span>  planners_[i]->getPlannerData(pd);</div>
<div class="line"><a name="l00635"></a><span class="lineno"> 635</span>  run[<span class="stringliteral">"graph states INTEGER"</span>] = std::to_string(pd.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a877a673801134168cba0581b277cae79">numVertices</a>());</div>
<div class="line"><a name="l00636"></a><span class="lineno"> 636</span>  run[<span class="stringliteral">"graph motions INTEGER"</span>] = std::to_string(pd.<a class="code" href="classompl_1_1base_1_1PlannerData.html#a383876c22dd92deeed0a536c10f7ecd4">numEdges</a>());</div>
<div class="line"><a name="l00637"></a><span class="lineno"> 637</span>  </div>
<div class="line"><a name="l00638"></a><span class="lineno"> 638</span>  <span class="keywordflow">for</span> (<span class="keyword">const</span> <span class="keyword">auto</span> &prop : pd.<a class="code" href="classompl_1_1base_1_1PlannerData.html#aca9e2da9d9a46e42c516fc8b926ab65c">properties</a>)</div>
<div class="line"><a name="l00639"></a><span class="lineno"> 639</span>  run[prop.first] = prop.second;</div>
<div class="line"><a name="l00640"></a><span class="lineno"> 640</span>  </div>
<div class="line"><a name="l00641"></a><span class="lineno"> 641</span>  <span class="comment">// execute post-run event, if set</span></div>
<div class="line"><a name="l00642"></a><span class="lineno"> 642</span>  <span class="keywordflow">try</span></div>
<div class="line"><a name="l00643"></a><span class="lineno"> 643</span>  {</div>
<div class="line"><a name="l00644"></a><span class="lineno"> 644</span>  <span class="keywordflow">if</span> (postRun_)</div>
<div class="line"><a name="l00645"></a><span class="lineno"> 645</span>  {</div>
<div class="line"><a name="l00646"></a><span class="lineno"> 646</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Executing post-run event for run %d of planner %s ..."</span>, status_.activeRun,</div>
<div class="line"><a name="l00647"></a><span class="lineno"> 647</span>  status_.activePlanner.c_str());</div>
<div class="line"><a name="l00648"></a><span class="lineno"> 648</span>  postRun_(planners_[i], run);</div>
<div class="line"><a name="l00649"></a><span class="lineno"> 649</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Completed execution of post-run event"</span>);</div>
<div class="line"><a name="l00650"></a><span class="lineno"> 650</span>  }</div>
<div class="line"><a name="l00651"></a><span class="lineno"> 651</span>  }</div>
<div class="line"><a name="l00652"></a><span class="lineno"> 652</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00653"></a><span class="lineno"> 653</span>  {</div>
<div class="line"><a name="l00654"></a><span class="lineno"> 654</span>  std::stringstream es;</div>
<div class="line"><a name="l00655"></a><span class="lineno"> 655</span>  es << <span class="stringliteral">"There was an error in the execution of the post-run event for run "</span> << status_.activeRun</div>
<div class="line"><a name="l00656"></a><span class="lineno"> 656</span>  << <span class="stringliteral">" of planner "</span> << status_.activePlanner << std::endl;</div>
<div class="line"><a name="l00657"></a><span class="lineno"> 657</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00658"></a><span class="lineno"> 658</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00659"></a><span class="lineno"> 659</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00660"></a><span class="lineno"> 660</span>  }</div>
<div class="line"><a name="l00661"></a><span class="lineno"> 661</span>  </div>
<div class="line"><a name="l00662"></a><span class="lineno"> 662</span>  exp_.planners[i].runs.push_back(run);</div>
<div class="line"><a name="l00663"></a><span class="lineno"> 663</span>  </div>
<div class="line"><a name="l00664"></a><span class="lineno"> 664</span>  <span class="comment">// Add planner progress data from the planner progress</span></div>
<div class="line"><a name="l00665"></a><span class="lineno"> 665</span>  <span class="comment">// collector if there was anything to report</span></div>
<div class="line"><a name="l00666"></a><span class="lineno"> 666</span>  <span class="keywordflow">if</span> (planners_[i]->getPlannerProgressProperties().size() > 0)</div>
<div class="line"><a name="l00667"></a><span class="lineno"> 667</span>  {</div>
<div class="line"><a name="l00668"></a><span class="lineno"> 668</span>  exp_.planners[i].runsProgressData.push_back(rp.getRunProgressData());</div>
<div class="line"><a name="l00669"></a><span class="lineno"> 669</span>  }</div>
<div class="line"><a name="l00670"></a><span class="lineno"> 670</span>  }</div>
<div class="line"><a name="l00671"></a><span class="lineno"> 671</span>  <span class="keywordflow">catch</span> (std::runtime_error &e)</div>
<div class="line"><a name="l00672"></a><span class="lineno"> 672</span>  {</div>
<div class="line"><a name="l00673"></a><span class="lineno"> 673</span>  std::stringstream es;</div>
<div class="line"><a name="l00674"></a><span class="lineno"> 674</span>  es << <span class="stringliteral">"There was an error in the extraction of planner results: planner = "</span> << status_.activePlanner</div>
<div class="line"><a name="l00675"></a><span class="lineno"> 675</span>  << <span class="stringliteral">", run = "</span> << status_.activePlanner << std::endl;</div>
<div class="line"><a name="l00676"></a><span class="lineno"> 676</span>  es << <span class="stringliteral">"*** "</span> << e.what() << std::endl;</div>
<div class="line"><a name="l00677"></a><span class="lineno"> 677</span>  std::cerr << es.str();</div>
<div class="line"><a name="l00678"></a><span class="lineno"> 678</span>  <a class="code" href="group__logging.html#ga05ad3ae88188e7f248748785afd2b882">OMPL_ERROR</a>(es.str().c_str());</div>
<div class="line"><a name="l00679"></a><span class="lineno"> 679</span>  }</div>
<div class="line"><a name="l00680"></a><span class="lineno"> 680</span>  </div>
<div class="line"><a name="l00681"></a><span class="lineno"> 681</span>  ++j;</div>
<div class="line"><a name="l00682"></a><span class="lineno"> 682</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a> == 0)</div>
<div class="line"><a name="l00683"></a><span class="lineno"> 683</span>  {</div>
<div class="line"><a name="l00684"></a><span class="lineno"> 684</span>  maxTime -= rp.getTimeUsed();</div>
<div class="line"><a name="l00685"></a><span class="lineno"> 685</span>  <span class="keywordflow">if</span> (maxTime < 0.)</div>
<div class="line"><a name="l00686"></a><span class="lineno"> 686</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00687"></a><span class="lineno"> 687</span>  }</div>
<div class="line"><a name="l00688"></a><span class="lineno"> 688</span>  <span class="keywordflow">else</span></div>
<div class="line"><a name="l00689"></a><span class="lineno"> 689</span>  {</div>
<div class="line"><a name="l00690"></a><span class="lineno"> 690</span>  <span class="keywordflow">if</span> (j >= req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">runCount</a>)</div>
<div class="line"><a name="l00691"></a><span class="lineno"> 691</span>  <span class="keywordflow">break</span>;</div>
<div class="line"><a name="l00692"></a><span class="lineno"> 692</span>  }</div>
<div class="line"><a name="l00693"></a><span class="lineno"> 693</span>  }</div>
<div class="line"><a name="l00694"></a><span class="lineno"> 694</span>  planners_[i]->clear();</div>
<div class="line"><a name="l00695"></a><span class="lineno"> 695</span>  }</div>
<div class="line"><a name="l00696"></a><span class="lineno"> 696</span>  </div>
<div class="line"><a name="l00697"></a><span class="lineno"> 697</span>  status_.running = <span class="keyword">false</span>;</div>
<div class="line"><a name="l00698"></a><span class="lineno"> 698</span>  status_.progressPercentage = 100.0;</div>
<div class="line"><a name="l00699"></a><span class="lineno"> 699</span>  <span class="keywordflow">if</span> (req.<a class="code" href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0e63ef873358346cfb78a69121dfd2ec">displayProgress</a>)</div>
<div class="line"><a name="l00700"></a><span class="lineno"> 700</span>  {</div>
<div class="line"><a name="l00701"></a><span class="lineno"> 701</span>  <span class="keywordflow">while</span> (status_.progressPercentage > progress->count())</div>
<div class="line"><a name="l00702"></a><span class="lineno"> 702</span>  ++(*progress);</div>
<div class="line"><a name="l00703"></a><span class="lineno"> 703</span>  std::cout << std::endl;</div>
<div class="line"><a name="l00704"></a><span class="lineno"> 704</span>  }</div>
<div class="line"><a name="l00705"></a><span class="lineno"> 705</span>  </div>
<div class="line"><a name="l00706"></a><span class="lineno"> 706</span>  exp_.totalDuration = <a class="code" href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">time::seconds</a>(<a class="code" href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">time::now</a>() - exp_.startTime);</div>
<div class="line"><a name="l00707"></a><span class="lineno"> 707</span>  </div>
<div class="line"><a name="l00708"></a><span class="lineno"> 708</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Benchmark complete"</span>);</div>
<div class="line"><a name="l00709"></a><span class="lineno"> 709</span>  <a class="code" href="namespaceompl_1_1msg.html#a66fd8fd39855d4166ff40164fe4d9d6b">msg::useOutputHandler</a>(oh);</div>
<div class="line"><a name="l00710"></a><span class="lineno"> 710</span>  <a class="code" href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a>(<span class="stringliteral">"Benchmark complete"</span>);</div>
<div class="line"><a name="l00711"></a><span class="lineno"> 711</span> }</div>
</div><!-- fragment --></div><!-- contents -->
<div class="ttc" id="anamespaceompl_1_1base_html_a5c218cde462780a4502dfc561708e903"><div class="ttname"><a href="namespaceompl_1_1base.html#a5c218cde462780a4502dfc561708e903">ompl::base::PlannerTerminationConditionFn</a></div><div class="ttdeci">std::function< bool()> PlannerTerminationConditionFn</div><div class="ttdoc">Signature for functions that decide whether termination conditions have been met for a planner,...</div><div class="ttdef"><b>Definition:</b> <a href="PlannerTerminationCondition_8h_source.html#l00120">PlannerTerminationCondition.h:120</a></div></div>
<div class="ttc" id="aclassompl_1_1time_1_1ProgressDisplay_html"><div class="ttname"><a href="classompl_1_1time_1_1ProgressDisplay.html">ompl::time::ProgressDisplay</a></div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00151">Time.h:151</a></div></div>
<div class="ttc" id="anamespaceompl_1_1time_html_a4bbc20223e0b408d4a59f453a1ae7a25"><div class="ttname"><a href="namespaceompl_1_1time.html#a4bbc20223e0b408d4a59f453a1ae7a25">ompl::time::point</a></div><div class="ttdeci">std::chrono::system_clock::time_point point</div><div class="ttdoc">Representation of a point in time.</div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00116">Time.h:116</a></div></div>
<div class="ttc" id="anamespaceompl_1_1machine_html_a72f733ca0ea9660e62e7d78887778494"><div class="ttname"><a href="namespaceompl_1_1machine.html#a72f733ca0ea9660e62e7d78887778494">ompl::machine::getHostname</a></div><div class="ttdeci">std::string getHostname()</div><div class="ttdoc">Get the hostname of the machine in use.</div></div>
<div class="ttc" id="anamespaceompl_1_1machine_html_a263d0e9d43cd9e10edb468b97f46a198"><div class="ttname"><a href="namespaceompl_1_1machine.html#a263d0e9d43cd9e10edb468b97f46a198">ompl::machine::getProcessMemoryUsage</a></div><div class="ttdeci">MemUsage_t getProcessMemoryUsage()</div><div class="ttdoc">Get the amount of memory the current process is using. This should work on major platforms (Windows,...</div></div>
<div class="ttc" id="anamespaceompl_1_1msg_html_a83e28f524a5576a73bb062523bbdc53d"><div class="ttname"><a href="namespaceompl_1_1msg.html#a83e28f524a5576a73bb062523bbdc53d">ompl::msg::noOutputHandler</a></div><div class="ttdeci">void noOutputHandler()</div><div class="ttdoc">This function instructs ompl that no messages should be outputted. Equivalent to useOutputHandler(nul...</div><div class="ttdef"><b>Definition:</b> <a href="Console_8cpp_source.html#l00095">Console.cpp:95</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1Planner_html_adc4df80108aec5db29373302e4b8d723"><div class="ttname"><a href="classompl_1_1base_1_1Planner.html#adc4df80108aec5db29373302e4b8d723">ompl::base::Planner::PlannerProgressProperties</a></div><div class="ttdeci">std::map< std::string, PlannerProgressProperty > PlannerProgressProperties</div><div class="ttdoc">A dictionary which maps the name of a progress property to the function to be used for querying that ...</div><div class="ttdef"><b>Definition:</b> <a href="Planner_8h_source.html#l00417">Planner.h:417</a></div></div>
<div class="ttc" id="aclassompl_1_1msg_1_1OutputHandler_html"><div class="ttname"><a href="classompl_1_1msg_1_1OutputHandler.html">ompl::msg::OutputHandler</a></div><div class="ttdoc">Generic class to handle output from a piece of code.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00102">Console.h:102</a></div></div>
<div class="ttc" id="anamespaceompl_1_1msg_html_a66fd8fd39855d4166ff40164fe4d9d6b"><div class="ttname"><a href="namespaceompl_1_1msg.html#a66fd8fd39855d4166ff40164fe4d9d6b">ompl::msg::useOutputHandler</a></div><div class="ttdeci">void useOutputHandler(OutputHandler *oh)</div><div class="ttdoc">Specify the instance of the OutputHandler to use. By default, this is OutputHandlerSTD.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8cpp_source.html#l00108">Console.cpp:108</a></div></div>
<div class="ttc" id="anamespaceompl_1_1machine_html_ab382994b8b47d80d0e7a2a7fb16c7a84"><div class="ttname"><a href="namespaceompl_1_1machine.html#ab382994b8b47d80d0e7a2a7fb16c7a84">ompl::machine::MemUsage_t</a></div><div class="ttdeci">unsigned long long MemUsage_t</div><div class="ttdoc">Amount of memory used, in bytes.</div><div class="ttdef"><b>Definition:</b> <a href="MachineSpecs_8h_source.html#l00112">MachineSpecs.h:112</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1Benchmark_html_a6a7267b64dbde28d9b505ffac55c217e"><div class="ttname"><a href="classompl_1_1tools_1_1Benchmark.html#a6a7267b64dbde28d9b505ffac55c217e">ompl::tools::Benchmark::exp_</a></div><div class="ttdeci">CompleteExperiment exp_</div><div class="ttdoc">The collected experimental data (for all planners)</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00434">Benchmark.h:434</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_ac9bdc9db7d5325710fb9ac74d27900ad"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#ac9bdc9db7d5325710fb9ac74d27900ad">ompl::base::PlannerStatus::asString</a></div><div class="ttdeci">std::string asString() const</div><div class="ttdoc">Return a string representation.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8cpp_source.html#l00039">PlannerStatus.cpp:39</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4ac60ae0f04326edcd4fa202cda3dddb33"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4ac60ae0f04326edcd4fa202cda3dddb33">ompl::base::PlannerStatus::TYPE_COUNT</a></div><div class="ttdeci">@ TYPE_COUNT</div><div class="ttdoc">The number of possible status values.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00202">PlannerStatus.h:202</a></div></div>
<div class="ttc" id="anamespaceompl_1_1time_html_a5da903c529cfbbce79900b7c1cbc6cc3"><div class="ttname"><a href="namespaceompl_1_1time.html#a5da903c529cfbbce79900b7c1cbc6cc3">ompl::time::now</a></div><div class="ttdeci">point now()</div><div class="ttdoc">Get the current time point.</div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00122">Time.h:122</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_a383876c22dd92deeed0a536c10f7ecd4"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#a383876c22dd92deeed0a536c10f7ecd4">ompl::base::PlannerData::numEdges</a></div><div class="ttdeci">unsigned int numEdges() const</div><div class="ttdoc">Retrieve the number of edges in this structure.</div><div class="ttdef"><b>Definition:</b> <a href="src_2ompl_2base_2src_2PlannerData_8cpp_source.html#l00207">PlannerData.cpp:207</a></div></div>
<div class="ttc" id="agroup__logging_html_ga04bc36d1b8c57ad7e13a8a48451a3a05"><div class="ttname"><a href="group__logging.html#ga04bc36d1b8c57ad7e13a8a48451a3a05">OMPL_INFORM</a></div><div class="ttdeci">#define OMPL_INFORM(fmt,...)</div><div class="ttdoc">Log a formatted information string.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00068">Console.h:68</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_af7c98e06da0e8b8181a5feec8b57ac6d"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#af7c98e06da0e8b8181a5feec8b57ac6d">ompl::tools::Benchmark::Request::simplify</a></div><div class="ttdeci">bool simplify</div><div class="ttdoc">flag indicating whether simplification should be applied to path; true by default</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00290">Benchmark.h:290</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html">ompl::base::PlannerData</a></div><div class="ttdoc">Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...</div><div class="ttdef"><b>Definition:</b> <a href="base_2PlannerData_8h_source.html#l00238">PlannerData.h:238</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_a0252082e35f936c93c86eabf0d713e01"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0252082e35f936c93c86eabf0d713e01">ompl::tools::Benchmark::Request::runCount</a></div><div class="ttdeci">unsigned int runCount</div><div class="ttdoc">the number of times to run each planner; 100 by default If set to 0, then run each planner as many ti...</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00276">Benchmark.h:276</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_a882d384685f86176fbb441c256d34044"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a882d384685f86176fbb441c256d34044">ompl::tools::Benchmark::Request::saveConsoleOutput</a></div><div class="ttdeci">bool saveConsoleOutput</div><div class="ttdoc">flag indicating whether console output is saved (in an automatically generated filename); true by def...</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00287">Benchmark.h:287</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_a877a673801134168cba0581b277cae79"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#a877a673801134168cba0581b277cae79">ompl::base::PlannerData::numVertices</a></div><div class="ttdeci">unsigned int numVertices() const</div><div class="ttdoc">Retrieve the number of vertices in this structure.</div><div class="ttdef"><b>Definition:</b> <a href="src_2ompl_2base_2src_2PlannerData_8cpp_source.html#l00202">PlannerData.cpp:202</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_a0e63ef873358346cfb78a69121dfd2ec"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a0e63ef873358346cfb78a69121dfd2ec">ompl::tools::Benchmark::Request::displayProgress</a></div><div class="ttdeci">bool displayProgress</div><div class="ttdoc">flag indicating whether progress is to be displayed or not; true by default</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00283">Benchmark.h:283</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1Benchmark_html_a979f5df0704b89e7da4a1c29ab857a02"><div class="ttname"><a href="classompl_1_1tools_1_1Benchmark.html#a979f5df0704b89e7da4a1c29ab857a02">ompl::tools::Benchmark::saveResultsToFile</a></div><div class="ttdeci">bool saveResultsToFile() const</div><div class="ttdoc">Save the results of the benchmark to a file. The name of the file is the current date and time.</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8cpp_source.html#l00220">Benchmark.cpp:220</a></div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html">ompl::base::PlannerStatus</a></div><div class="ttdoc">A class to store the exit status of Planner::solve()</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00112">PlannerStatus.h:112</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html">ompl::tools::Benchmark::Request</a></div><div class="ttdoc">Representation of a benchmark request.</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00252">Benchmark.h:252</a></div></div>
<div class="ttc" id="aclassompl_1_1msg_1_1OutputHandlerFile_html"><div class="ttname"><a href="classompl_1_1msg_1_1OutputHandlerFile.html">ompl::msg::OutputHandlerFile</a></div><div class="ttdoc">Implementation of OutputHandler that saves messages in a file.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00125">Console.h:125</a></div></div>
<div class="ttc" id="aclassompl_1_1RNG_html_a9b59291cc9599888d41a1b7a748aa5fe"><div class="ttname"><a href="classompl_1_1RNG.html#a9b59291cc9599888d41a1b7a748aa5fe">ompl::RNG::getSeed</a></div><div class="ttdeci">static std::uint_fast32_t getSeed()</div><div class="ttdoc">Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed()...</div><div class="ttdef"><b>Definition:</b> <a href="RandomNumbers_8cpp_source.html#l00208">RandomNumbers.cpp:208</a></div></div>
<div class="ttc" id="anamespaceompl_1_1time_html_ae77961d01352b61e3fcd521ec3e5d59a"><div class="ttname"><a href="namespaceompl_1_1time.html#ae77961d01352b61e3fcd521ec3e5d59a">ompl::time::duration</a></div><div class="ttdeci">std::chrono::system_clock::duration duration</div><div class="ttdoc">Representation of a time duration.</div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00119">Time.h:119</a></div></div>
<div class="ttc" id="agroup__logging_html_gab76357dced39cb468d2061d3358f80a6"><div class="ttname"><a href="group__logging.html#gab76357dced39cb468d2061d3358f80a6">OMPL_WARN</a></div><div class="ttdeci">#define OMPL_WARN(fmt,...)</div><div class="ttdoc">Log a formatted warning string.</div><div class="ttdef"><b>Definition:</b> <a href="Console_8h_source.html#l00066">Console.h:66</a></div></div>
<div class="ttc" id="aclassompl_1_1base_1_1PlannerData_html_aca9e2da9d9a46e42c516fc8b926ab65c"><div class="ttname"><a href="classompl_1_1base_1_1PlannerData.html#aca9e2da9d9a46e42c516fc8b926ab65c">ompl::base::PlannerData::properties</a></div><div class="ttdeci">std::map< std::string, std::string > properties</div><div class="ttdoc">Any extra properties (key-value pairs) the planner can set.</div><div class="ttdef"><b>Definition:</b> <a href="base_2PlannerData_8h_source.html#l00474">PlannerData.h:474</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1Benchmark_html_a3257cb8dccc15037e81c0f235c61a7e8"><div class="ttname"><a href="classompl_1_1tools_1_1Benchmark.html#a3257cb8dccc15037e81c0f235c61a7e8">ompl::tools::Benchmark::benchmark</a></div><div class="ttdeci">virtual void benchmark(const Request &req)</div><div class="ttdoc">Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8cpp_source.html#l00353">Benchmark.cpp:353</a></div></div>
<div class="ttc" id="anamespaceompl_1_1machine_html_a75c4da4e42a1de9050a171213135fa26"><div class="ttname"><a href="namespaceompl_1_1machine.html#a75c4da4e42a1de9050a171213135fa26">ompl::machine::getCPUInfo</a></div><div class="ttdeci">std::string getCPUInfo()</div><div class="ttdoc">Get information about the CPU of the machine in use.</div></div>
<div class="ttc" id="astructompl_1_1base_1_1PlannerStatus_html_a5fe3825813b066b664b3dd34dd1bc8c4"><div class="ttname"><a href="structompl_1_1base_1_1PlannerStatus.html#a5fe3825813b066b664b3dd34dd1bc8c4">ompl::base::PlannerStatus::StatusType</a></div><div class="ttdeci">StatusType</div><div class="ttdoc">The possible values of the status returned by a planner.</div><div class="ttdef"><b>Definition:</b> <a href="PlannerStatus_8h_source.html#l00147">PlannerStatus.h:147</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_a12b3d959f8e7349120cdd87ef21f72b8"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a12b3d959f8e7349120cdd87ef21f72b8">ompl::tools::Benchmark::Request::maxMem</a></div><div class="ttdeci">double maxMem</div><div class="ttdoc">the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00272">Benchmark.h:272</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="anamespaceompl_1_1time_html_ae8d794354a37128403aba90a187fe532"><div class="ttname"><a href="namespaceompl_1_1time.html#ae8d794354a37128403aba90a187fe532">ompl::time::as_string</a></div><div class="ttdeci">std::string as_string(const point &p)</div><div class="ttdoc">Return string representation of point in time.</div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00142">Time.h:142</a></div></div>
<div class="ttc" id="anamespaceompl_1_1msg_html_a0e9a5d161592281f8caf01b0c8b2e746"><div class="ttname"><a href="namespaceompl_1_1msg.html#a0e9a5d161592281f8caf01b0c8b2e746">ompl::msg::getOutputHandler</a></div><div class="ttdeci">OutputHandler * getOutputHandler()</div><div class="ttdoc">Get the instance of the OutputHandler currently used. This is nullptr in case there is no output hand...</div><div class="ttdef"><b>Definition:</b> <a href="Console_8cpp_source.html#l00115">Console.cpp:115</a></div></div>
<div class="ttc" id="anamespaceompl_html_a6e6c38ce80fbb8f10d826bb19b64735a"><div class="ttname"><a href="namespaceompl.html#a6e6c38ce80fbb8f10d826bb19b64735a">ompl::toString</a></div><div class="ttdeci">std::string toString(float val)</div><div class="ttdoc">convert float to string using classic "C" locale semantics</div><div class="ttdef"><b>Definition:</b> <a href="String_8cpp_source.html#l00082">String.cpp:82</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1Benchmark_html_ad660e80e710f6fd524d865bc232311e5"><div class="ttname"><a href="classompl_1_1tools_1_1Benchmark.html#ad660e80e710f6fd524d865bc232311e5">ompl::tools::Benchmark::RunProperties</a></div><div class="ttdeci">std::map< std::string, std::string > RunProperties</div><div class="ttdoc">The data collected from a run of a planner is stored as key-value pairs.</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00175">Benchmark.h:175</a></div></div>
<div class="ttc" id="anamespaceompl_1_1time_html_acac374ab4374adb207edb38cedb7fbb1"><div class="ttname"><a href="namespaceompl_1_1time.html#acac374ab4374adb207edb38cedb7fbb1">ompl::time::seconds</a></div><div class="ttdeci">duration seconds(double sec)</div><div class="ttdoc">Return the time duration representing a given number of seconds.</div><div class="ttdef"><b>Definition:</b> <a href="Time_8h_source.html#l00128">Time.h:128</a></div></div>
<div class="ttc" id="aclassompl_1_1tools_1_1Benchmark_html_a9f63b0b4e3de67b937bfa3022caf7348"><div class="ttname"><a href="classompl_1_1tools_1_1Benchmark.html#a9f63b0b4e3de67b937bfa3022caf7348">ompl::tools::Benchmark::saveResultsToStream</a></div><div class="ttdeci">virtual bool saveResultsToStream(std::ostream &out=std::cout) const</div><div class="ttdoc">Save the results of the benchmark to a stream.</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8cpp_source.html#l00226">Benchmark.cpp:226</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_a7f308d71127840e12c6fedfe2668d652"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#a7f308d71127840e12c6fedfe2668d652">ompl::tools::Benchmark::Request::timeBetweenUpdates</a></div><div class="ttdeci">double timeBetweenUpdates</div><div class="ttdoc">When collecting time-varying data from a planner during its execution, the planner's progress will be...</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00280">Benchmark.h:280</a></div></div>
<div class="ttc" id="anamespaceompl_html"><div class="ttname"><a href="namespaceompl.html">ompl</a></div><div class="ttdoc">Main namespace. Contains everything in this library.</div><div class="ttdef"><b>Definition:</b> <a href="AppBase_8h_source.html#l00021">AppBase.h:21</a></div></div>
<div class="ttc" id="astructompl_1_1tools_1_1Benchmark_1_1Request_html_ae29e119a2a3ca7d1325f701159a7636a"><div class="ttname"><a href="structompl_1_1tools_1_1Benchmark_1_1Request.html#ae29e119a2a3ca7d1325f701159a7636a">ompl::tools::Benchmark::Request::maxTime</a></div><div class="ttdeci">double maxTime</div><div class="ttdoc">the maximum amount of time a planner is allowed to run (seconds); 5.0 by default</div><div class="ttdef"><b>Definition:</b> <a href="Benchmark_8h_source.html#l00269">Benchmark.h:269</a></div></div>
</div>
<footer class="footer">
<div class="container">
<a href="http://www.kavrakilab.org">Kavraki Lab</a> •
<a href="https://www.cs.rice.edu">Department of Computer Science</a> •
<a href="https://www.rice.edu">Rice University</a><br/>
Funded in part by the <a href="https://www.nsf.gov">National Science Foundation</a><br/>
Documentation generated by <a href="http://www.doxygen.org/index.html">doxygen</a> 1.8.17
</div>
</footer>
<script>
(function(i,s,o,g,r,a,m){i['GoogleAnalyticsObject']=r;i[r]=i[r]||function(){
(i[r].q=i[r].q||[]).push(arguments)},i[r].l=1*new Date();a=s.createElement(o),
m=s.getElementsByTagName(o)[0];a.async=1;a.src=g;m.parentNode.insertBefore(a,m)
})(window,document,'script','//www.google-analytics.com/analytics.js','ga');
ga('create', 'UA-9156598-2', 'auto');
ga('send', 'pageview');
</script>
<script src="https://cdnjs.cloudflare.com/ajax/libs/popper.js/1.14.7/umd/popper.min.js" integrity="sha384-UO2eT0CpHqdSJQ6hJty5KVphtPhzWj9WO1clHTMGa3JDZwrnQq4sF86dIHNDz0W1" crossorigin="anonymous"></script>
<script src="https://stackpath.bootstrapcdn.com/bootstrap/4.3.1/js/bootstrap.min.js" integrity="sha384-JjSmVgyd0p3pXB1rRibZUAYoIIy6OrQ6VrjIEaFf/nJGzIxFDsf4x0xIM+B07jRM" crossorigin="anonymous"></script>
</body>
</html>