Loading...
Searching...
No Matches
Benchmark.cpp
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan, Luis G. Torres */
36
37#include "ompl/tools/benchmark/Benchmark.h"
38#include "ompl/tools/benchmark/MachineSpecs.h"
39#include "ompl/util/Time.h"
40#include "ompl/config.h"
41#include "ompl/util/String.h"
42#include <boost/scoped_ptr.hpp>
43#include <thread>
44#include <mutex>
45#include <condition_variable>
46#include <fstream>
47#include <sstream>
48
50namespace ompl
51{
52 namespace tools
53 {
56 static std::string getResultsFilename(const Benchmark::CompleteExperiment &exp)
57 {
58 return "ompl_" + exp.host + "_" + time::as_string(exp.startTime) + ".log";
59 }
60
63 static std::string getConsoleFilename(const Benchmark::CompleteExperiment &exp)
64 {
65 return "ompl_" + exp.host + "_" + time::as_string(exp.startTime) + ".console";
66 }
67
68 static bool terminationCondition(const machine::MemUsage_t maxMem, const time::point &endTime)
69 {
70 if (time::now() < endTime && machine::getProcessMemoryUsage() < maxMem)
71 return false;
72 return true;
73 }
74
75 class RunPlanner
76 {
77 public:
78 RunPlanner(const Benchmark *benchmark) : benchmark_(benchmark), timeUsed_(0.0), memUsed_(0)
79 {
80 }
81
82 void run(const base::PlannerPtr &planner, const machine::MemUsage_t memStart,
83 const machine::MemUsage_t maxMem, const double maxTime, const double timeBetweenUpdates)
84 {
85 runThread(planner, memStart + maxMem, time::seconds(maxTime), time::seconds(timeBetweenUpdates));
86 }
87
88 double getTimeUsed() const
89 {
90 return timeUsed_;
91 }
92
93 machine::MemUsage_t getMemUsed() const
94 {
95 return memUsed_;
96 }
97
98 base::PlannerStatus getStatus() const
99 {
100 return status_;
101 }
102
103 const Benchmark::RunProgressData &getRunProgressData() const
104 {
105 return runProgressData_;
106 }
107
108 private:
109 void runThread(const base::PlannerPtr &planner, const machine::MemUsage_t maxMem,
110 const time::duration &maxDuration, const time::duration &timeBetweenUpdates)
111 {
112 time::point timeStart = time::now();
113
114 try
115 {
116 const time::point endtime = time::now() + maxDuration;
117 base::PlannerTerminationConditionFn ptc([maxMem, endtime]
118 { return terminationCondition(maxMem, endtime); });
119 solved_ = false;
120 // Only launch the planner progress property
121 // collector if there is any data for it to report
122 //
123 // \todo issue here is that at least one sample
124 // always gets taken before planner even starts;
125 // might be worth adding a short wait time before
126 // collector begins sampling
127 boost::scoped_ptr<std::thread> t;
128 if (planner->getPlannerProgressProperties().size() > 0)
129 t.reset(new std::thread(
130 [this, &planner, timeBetweenUpdates]
131 {
132 collectProgressProperties(planner->getPlannerProgressProperties(), timeBetweenUpdates);
133 }));
134 status_ = planner->solve(ptc, 0.1);
135 solvedFlag_.lock();
136 solved_ = true;
137 solvedCondition_.notify_all();
138 solvedFlag_.unlock();
139 if (t)
140 t->join(); // maybe look into interrupting even if planner throws an exception
141 }
142 catch (std::runtime_error &e)
143 {
144 std::stringstream es;
145 es << "There was an error executing planner " << benchmark_->getStatus().activePlanner
146 << ", run = " << benchmark_->getStatus().activeRun << std::endl;
147 es << "*** " << e.what() << std::endl;
148 std::cerr << es.str();
149 OMPL_ERROR(es.str().c_str());
150 }
151
152 timeUsed_ = time::seconds(time::now() - timeStart);
153 memUsed_ = machine::getProcessMemoryUsage();
154 }
155
156 void collectProgressProperties(const base::Planner::PlannerProgressProperties &properties,
157 const time::duration &timePerUpdate)
158 {
159 time::point timeStart = time::now();
160
161 std::unique_lock<std::mutex> ulock(solvedFlag_);
162 while (!solved_)
163 {
164 if (solvedCondition_.wait_for(ulock, timePerUpdate) == std::cv_status::no_timeout)
165 return;
166 else
167 {
168 double timeInSeconds = time::seconds(time::now() - timeStart);
169 std::string timeStamp = ompl::toString(timeInSeconds);
170 std::map<std::string, std::string> data;
171 data["time REAL"] = timeStamp;
172 for (const auto &property : properties)
173 {
174 data[property.first] = property.second();
175 }
176 runProgressData_.push_back(data);
177 }
178 }
179 }
180
181 const Benchmark *benchmark_;
182 double timeUsed_;
183 machine::MemUsage_t memUsed_;
184 base::PlannerStatus status_;
185 Benchmark::RunProgressData runProgressData_;
186
187 // variables needed for progress property collection
188 bool solved_;
189 std::mutex solvedFlag_;
190 std::condition_variable solvedCondition_;
191 };
192 } // namespace tools
193} // namespace ompl
195
197 : gsetup_(&setup), csetup_(nullptr)
198{
199 exp_.name = name;
200}
201
203 : gsetup_(nullptr), csetup_(&setup)
204{
205 exp_.name = name;
206}
207
208void ompl::tools::Benchmark::addExperimentParameter(const std::string &name, const std::string &type,
209 const std::string &value)
210{
211 exp_.parameters[name + " " + type] = value;
212}
213
214const std::map<std::string, std::string> &ompl::tools::Benchmark::getExperimentParameters() const
215{
216 return exp_.parameters;
217}
218
220{
221 return exp_.parameters.size();
222}
223
224void ompl::tools::Benchmark::setExperimentName(const std::string &name)
225{
226 exp_.name = name;
227}
228
230{
231 return exp_.name;
232}
233
234void ompl::tools::Benchmark::addPlanner(const base::PlannerPtr &planner)
235{
236 if (planner && planner->getSpaceInformation().get() != (gsetup_ != nullptr ? gsetup_->getSpaceInformation().get() :
237 csetup_->getSpaceInformation().get()))
238 throw Exception("Planner instance does not match space information");
239 planners_.push_back(planner);
240}
241
243{
244 planners_.push_back(pa(gsetup_ != nullptr ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation()));
245}
246
251
256
259{
260 preRun_ = event;
261}
262
265{
266 postRun_ = event;
267}
268
273
278
279bool ompl::tools::Benchmark::saveResultsToFile(const char *filename) const
280{
281 bool result = false;
282
283 std::ofstream fout(filename);
284 if (fout.good())
285 {
286 result = saveResultsToStream(fout);
287 OMPL_INFORM("Results saved to '%s'", filename);
288 }
289 else
290 {
291 // try to save to a different file, if we can
292 if (getResultsFilename(exp_) != std::string(filename))
293 result = saveResultsToFile();
294
295 OMPL_ERROR("Unable to write results to '%s'", filename);
296 }
297 return result;
298}
299
301{
302 std::string filename = getResultsFilename(exp_);
303 return saveResultsToFile(filename.c_str());
304}
305
307{
308 if (exp_.planners.empty())
309 {
310 OMPL_WARN("There is no experimental data to save");
311 return false;
312 }
313
314 if (!out.good())
315 {
316 OMPL_ERROR("Unable to write to stream");
317 return false;
318 }
319
320 out << "OMPL version " << OMPL_VERSION << std::endl;
321 out << "Experiment " << (exp_.name.empty() ? "NO_NAME" : exp_.name) << std::endl;
322
323 out << exp_.parameters.size() << " experiment properties" << std::endl;
324 for (const auto &parameter : exp_.parameters)
325 out << parameter.first << " = " << parameter.second << std::endl;
326
327 out << "Running on " << (exp_.host.empty() ? "UNKNOWN" : exp_.host) << std::endl;
328 out << "Starting at " << time::as_string(exp_.startTime) << std::endl;
329 out << "<<<|" << std::endl << exp_.setupInfo << "|>>>" << std::endl;
330 out << "<<<|" << std::endl << exp_.cpuInfo << "|>>>" << std::endl;
331
332 out << exp_.seed << " is the random seed" << std::endl;
333 out << exp_.maxTime << " seconds per run" << std::endl;
334 out << exp_.maxMem << " MB per run" << std::endl;
335 out << exp_.runCount << " runs per planner" << std::endl;
336 out << exp_.totalDuration << " seconds spent to collect the data" << std::endl;
337
338 // change this if more enum types are added
339 out << "1 enum type" << std::endl;
340 out << "status";
341 for (unsigned int i = 0; i < base::PlannerStatus::TYPE_COUNT; ++i)
342 out << '|' << base::PlannerStatus(static_cast<base::PlannerStatus::StatusType>(i)).asString();
343 out << std::endl;
344
345 out << exp_.planners.size() << " planners" << std::endl;
346
347 for (const auto &planner : exp_.planners)
348 {
349 out << planner.name << std::endl;
350
351 // get names of common properties
352 std::vector<std::string> properties;
353 for (auto &property : planner.common)
354 properties.push_back(property.first);
355 std::sort(properties.begin(), properties.end());
356
357 // print names & values of common properties
358 out << properties.size() << " common properties" << std::endl;
359 for (auto &property : properties)
360 {
361 auto it = planner.common.find(property);
362 out << it->first << " = " << it->second << std::endl;
363 }
364
365 // construct the list of all possible properties for all runs
366 std::map<std::string, bool> propSeen;
367 for (auto &run : planner.runs)
368 for (auto &property : run)
369 propSeen[property.first] = true;
370
371 properties.clear();
372
373 for (auto &it : propSeen)
374 properties.push_back(it.first);
375 std::sort(properties.begin(), properties.end());
376
377 // print the property names
378 out << properties.size() << " properties for each run" << std::endl;
379 for (auto &property : properties)
380 out << property << std::endl;
381
382 // print the data for each run
383 out << planner.runs.size() << " runs" << std::endl;
384 for (auto &run : planner.runs)
385 {
386 for (auto &property : properties)
387 {
388 auto it = run.find(property);
389 if (it != run.end())
390 out << it->second;
391 out << "; ";
392 }
393 out << std::endl;
394 }
395
396 // print the run progress data if it was reported
397 if (planner.runsProgressData.size() > 0)
398 {
399 // Print number of progress properties
400 out << planner.progressPropertyNames.size() << " progress properties for each run" << std::endl;
401 // Print progress property names
402 for (const auto &progPropName : planner.progressPropertyNames)
403 {
404 out << progPropName << std::endl;
405 }
406 // Print progress properties for each run
407 out << planner.runsProgressData.size() << " runs" << std::endl;
408 for (const auto &r : planner.runsProgressData)
409 {
410 // For each time point
411 for (const auto &t : r)
412 {
413 // Print each of the properties at that time point
414 for (const auto &iter : t)
415 {
416 out << iter.second << ",";
417 }
418
419 // Separate time points by semicolons
420 out << ";";
421 }
422
423 // Separate runs by newlines
424 out << std::endl;
425 }
426 }
427
428 out << '.' << std::endl;
429 }
430 return true;
431}
432
434{
435 // sanity checks
436 if (gsetup_)
437 {
438 if (!gsetup_->getSpaceInformation()->isSetup())
439 gsetup_->getSpaceInformation()->setup();
440 }
441 else
442 {
443 if (!csetup_->getSpaceInformation()->isSetup())
444 csetup_->getSpaceInformation()->setup();
445 }
446
447 if (!(gsetup_ ? gsetup_->getGoal() : csetup_->getGoal()))
448 {
449 OMPL_ERROR("No goal defined");
450 return;
451 }
452
453 if (planners_.empty())
454 {
455 OMPL_ERROR("There are no planners to benchmark");
456 return;
457 }
458
459 status_.running = true;
460 exp_.totalDuration = 0.0;
461 exp_.maxTime = req.maxTime;
462 exp_.maxMem = req.maxMem;
463 exp_.runCount = req.runCount;
464 exp_.host = machine::getHostname();
465 exp_.cpuInfo = machine::getCPUInfo();
466 exp_.seed = RNG::getSeed();
467
468 exp_.startTime = time::now();
469
470 OMPL_INFORM("Configuring planners ...");
471
472 // clear previous experimental data
473 exp_.planners.clear();
474 exp_.planners.resize(planners_.size());
475
476 const base::ProblemDefinitionPtr &pdef =
477 gsetup_ ? gsetup_->getProblemDefinition() : csetup_->getProblemDefinition();
478 // set up all the planners
479 for (unsigned int i = 0; i < planners_.size(); ++i)
480 {
481 // configure the planner
482 planners_[i]->setProblemDefinition(pdef);
483 if (!planners_[i]->isSetup())
484 planners_[i]->setup();
485 exp_.planners[i].name = (gsetup_ ? "geometric_" : "control_") + planners_[i]->getName();
486 OMPL_INFORM("Configured %s", exp_.planners[i].name.c_str());
487 }
488
489 OMPL_INFORM("Done configuring planners.");
490 OMPL_INFORM("Saving planner setup information ...");
491
492 std::stringstream setupInfo;
493 if (gsetup_)
494 gsetup_->print(setupInfo);
495 else
496 csetup_->print(setupInfo);
497 setupInfo << std::endl << "Properties of benchmarked planners:" << std::endl;
498 for (auto &planner : planners_)
499 planner->printProperties(setupInfo);
500
501 exp_.setupInfo = setupInfo.str();
502
503 OMPL_INFORM("Done saving information");
504
505 OMPL_INFORM("Beginning benchmark");
507 boost::scoped_ptr<msg::OutputHandlerFile> ohf;
508 if (req.saveConsoleOutput)
509 {
510 ohf.reset(new msg::OutputHandlerFile(getConsoleFilename(exp_).c_str()));
511 msg::useOutputHandler(ohf.get());
512 }
513 else
515 OMPL_INFORM("Beginning benchmark");
516
517 boost::scoped_ptr<ompl::time::ProgressDisplay> progress;
518 if (req.displayProgress)
519 {
520 std::cout << "Running experiment " << exp_.name << "." << std::endl;
521 if (req.runCount)
522 std::cout << "Each planner will be executed " << req.runCount << " times for at most " << req.maxTime
523 << " seconds.";
524 else
525 std::cout << "Each planner will be executed as many times as possible within " << req.maxTime
526 << " seconds.";
527 std::cout << " Memory is limited at " << req.maxMem << "MB." << std::endl;
528 progress.reset(new ompl::time::ProgressDisplay);
529 }
530
532 auto maxMemBytes = (machine::MemUsage_t)(req.maxMem * 1024 * 1024);
533
534 for (unsigned int i = 0; i < planners_.size(); ++i)
535 {
536 status_.activePlanner = exp_.planners[i].name;
537 // execute planner switch event, if set
538 try
539 {
540 if (plannerSwitch_)
541 {
542 OMPL_INFORM("Executing planner-switch event for planner %s ...", status_.activePlanner.c_str());
544 OMPL_INFORM("Completed execution of planner-switch event");
545 }
546 }
547 catch (std::runtime_error &e)
548 {
549 std::stringstream es;
550 es << "There was an error executing the planner-switch event for planner " << status_.activePlanner
551 << std::endl;
552 es << "*** " << e.what() << std::endl;
553 std::cerr << es.str();
554 OMPL_ERROR(es.str().c_str());
555 }
556 if (gsetup_)
557 gsetup_->setup();
558 else
559 csetup_->setup();
560 planners_[i]->params().getParams(exp_.planners[i].common);
561 planners_[i]->getSpaceInformation()->params().getParams(exp_.planners[i].common);
562
563 // Add planner progress property names to struct
564 exp_.planners[i].progressPropertyNames.emplace_back("time REAL");
565 for (const auto &property : planners_[i]->getPlannerProgressProperties())
566 {
567 exp_.planners[i].progressPropertyNames.push_back(property.first);
568 }
569 std::sort(exp_.planners[i].progressPropertyNames.begin(), exp_.planners[i].progressPropertyNames.end());
570
571 // run the planner
572 double maxTime = req.maxTime;
573 unsigned int j = 0;
574 while (true)
575 {
576 status_.activeRun = j;
577 status_.progressPercentage =
578 req.runCount ? (double)(100 * (req.runCount * i + j)) / (double)(planners_.size() * req.runCount) :
579 (double)(100 * i) / (double)(planners_.size());
580
581 if (req.displayProgress)
582 while (status_.progressPercentage > progress->count())
583 ++(*progress);
584
585 OMPL_INFORM("Preparing for run %d of %s", status_.activeRun, status_.activePlanner.c_str());
586
587 // make sure all planning data structures are cleared
588 try
589 {
590 planners_[i]->clear();
591 if (gsetup_)
592 {
593 gsetup_->getProblemDefinition()->clearSolutionPaths();
594 gsetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
595 }
596 else
597 {
598 csetup_->getProblemDefinition()->clearSolutionPaths();
599 csetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
600 }
601 }
602 catch (std::runtime_error &e)
603 {
604 std::stringstream es;
605 es << "There was an error while preparing for run " << status_.activeRun << " of planner "
606 << status_.activePlanner << std::endl;
607 es << "*** " << e.what() << std::endl;
608 std::cerr << es.str();
609 OMPL_ERROR(es.str().c_str());
610 }
611
612 // execute pre-run event, if set
613 try
614 {
615 if (preRun_)
616 {
617 OMPL_INFORM("Executing pre-run event for run %d of planner %s ...", status_.activeRun,
618 status_.activePlanner.c_str());
619 preRun_(planners_[i]);
620 OMPL_INFORM("Completed execution of pre-run event");
621 }
622 }
623 catch (std::runtime_error &e)
624 {
625 std::stringstream es;
626 es << "There was an error executing the pre-run event for run " << status_.activeRun << " of planner "
627 << status_.activePlanner << std::endl;
628 es << "*** " << e.what() << std::endl;
629 std::cerr << es.str();
630 OMPL_ERROR(es.str().c_str());
631 }
632
633 RunPlanner rp(this);
634 rp.run(planners_[i], memStart, maxMemBytes, maxTime, req.timeBetweenUpdates);
635 bool solved = gsetup_ ? gsetup_->haveSolutionPath() : csetup_->haveSolutionPath();
636
637 // store results
638 try
639 {
640 RunProperties run;
641
642 run["time REAL"] = ompl::toString(rp.getTimeUsed());
643 run["memory REAL"] = ompl::toString((double)rp.getMemUsed() / (1024.0 * 1024.0));
644 run["status ENUM"] = std::to_string((int)static_cast<base::PlannerStatus::StatusType>(rp.getStatus()));
645 if (gsetup_)
646 {
647 run["solved BOOLEAN"] = std::to_string(gsetup_->haveExactSolutionPath());
648 run["valid segment fraction REAL"] =
649 ompl::toString(gsetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());
650 }
651 else
652 {
653 run["solved BOOLEAN"] = std::to_string(csetup_->haveExactSolutionPath());
654 run["valid segment fraction REAL"] =
655 ompl::toString(csetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());
656 }
657
658 if (solved)
659 {
660 if (gsetup_)
661 {
662 run["approximate solution BOOLEAN"] =
663 std::to_string(gsetup_->getProblemDefinition()->hasApproximateSolution());
664 run["solution difference REAL"] =
665 ompl::toString(gsetup_->getProblemDefinition()->getSolutionDifference());
666 run["solution length REAL"] = ompl::toString(gsetup_->getSolutionPath().length());
667 run["solution smoothness REAL"] = ompl::toString(gsetup_->getSolutionPath().smoothness());
668 run["solution clearance REAL"] = ompl::toString(gsetup_->getSolutionPath().clearance());
669 run["solution segments INTEGER"] =
670 std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);
671 run["correct solution BOOLEAN"] = std::to_string(gsetup_->getSolutionPath().check());
672
673 unsigned int factor = gsetup_->getStateSpace()->getValidSegmentCountFactor();
674 gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);
675 run["correct solution strict BOOLEAN"] = std::to_string(gsetup_->getSolutionPath().check());
676 gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);
677
678 if (req.simplify)
679 {
680 // simplify solution
681 time::point timeStart = time::now();
682 gsetup_->simplifySolution();
683 double timeUsed = time::seconds(time::now() - timeStart);
684 run["simplification time REAL"] = ompl::toString(timeUsed);
685 run["simplified solution length REAL"] =
686 ompl::toString(gsetup_->getSolutionPath().length());
687 run["simplified solution smoothness REAL"] =
688 ompl::toString(gsetup_->getSolutionPath().smoothness());
689 run["simplified solution clearance REAL"] =
690 ompl::toString(gsetup_->getSolutionPath().clearance());
691 run["simplified solution segments INTEGER"] =
692 std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);
693 run["simplified correct solution BOOLEAN"] =
694 std::to_string(gsetup_->getSolutionPath().check());
695 gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);
696 run["simplified correct solution strict BOOLEAN"] =
697 std::to_string(gsetup_->getSolutionPath().check());
698 gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);
699 }
700 }
701 else
702 {
703 run["approximate solution BOOLEAN"] =
704 std::to_string(csetup_->getProblemDefinition()->hasApproximateSolution());
705 run["solution difference REAL"] =
706 ompl::toString(csetup_->getProblemDefinition()->getSolutionDifference());
707 run["solution length REAL"] = ompl::toString(csetup_->getSolutionPath().length());
708 run["solution clearance REAL"] =
709 ompl::toString(csetup_->getSolutionPath().asGeometric().clearance());
710 run["solution segments INTEGER"] = std::to_string(csetup_->getSolutionPath().getControlCount());
711 run["correct solution BOOLEAN"] = std::to_string(csetup_->getSolutionPath().check());
712 }
713 }
714
715 base::PlannerData pd(gsetup_ ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation());
716 planners_[i]->getPlannerData(pd);
717 run["graph states INTEGER"] = std::to_string(pd.numVertices());
718 run["graph motions INTEGER"] = std::to_string(pd.numEdges());
719
720 for (const auto &prop : pd.properties)
721 run[prop.first] = prop.second;
722
723 // execute post-run event, if set
724 try
725 {
726 if (postRun_)
727 {
728 OMPL_INFORM("Executing post-run event for run %d of planner %s ...", status_.activeRun,
729 status_.activePlanner.c_str());
730 postRun_(planners_[i], run);
731 OMPL_INFORM("Completed execution of post-run event");
732 }
733 }
734 catch (std::runtime_error &e)
735 {
736 std::stringstream es;
737 es << "There was an error in the execution of the post-run event for run " << status_.activeRun
738 << " of planner " << status_.activePlanner << std::endl;
739 es << "*** " << e.what() << std::endl;
740 std::cerr << es.str();
741 OMPL_ERROR(es.str().c_str());
742 }
743
744 exp_.planners[i].runs.push_back(run);
745
746 // Add planner progress data from the planner progress
747 // collector if there was anything to report
748 if (planners_[i]->getPlannerProgressProperties().size() > 0)
749 {
750 exp_.planners[i].runsProgressData.push_back(rp.getRunProgressData());
751 }
752 }
753 catch (std::runtime_error &e)
754 {
755 std::stringstream es;
756 es << "There was an error in the extraction of planner results: planner = " << status_.activePlanner
757 << ", run = " << status_.activePlanner << std::endl;
758 es << "*** " << e.what() << std::endl;
759 std::cerr << es.str();
760 OMPL_ERROR(es.str().c_str());
761 }
762
763 ++j;
764 if (req.runCount == 0)
765 {
766 maxTime -= rp.getTimeUsed();
767 if (maxTime < 0.)
768 break;
769 }
770 else
771 {
772 if (j >= req.runCount)
773 break;
774 }
775 }
776 planners_[i]->clear();
777 }
778
779 status_.running = false;
780 status_.progressPercentage = 100.0;
781 if (req.displayProgress)
782 {
783 while (status_.progressPercentage > progress->count())
784 ++(*progress);
785 std::cout << std::endl;
786 }
787
788 exp_.totalDuration = time::seconds(time::now() - exp_.startTime);
789
790 OMPL_INFORM("Benchmark complete");
792 OMPL_INFORM("Benchmark complete");
793}
The exception type for ompl.
Definition Exception.h:47
static std::uint_fast32_t getSeed()
Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed()...
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
unsigned int numEdges() const
Retrieve the number of edges in this structure.
unsigned int numVertices() const
Retrieve the number of vertices in this structure.
std::map< std::string, std::string > properties
Any extra properties (key-value pairs) the planner can set.
std::map< std::string, PlannerProgressProperty > PlannerProgressProperties
A dictionary which maps the name of a progress property to the function to be used for querying that ...
Definition Planner.h:353
Create the set of classes typically needed to solve a control problem.
Definition SimpleSetup.h:63
Create the set of classes typically needed to solve a geometric problem.
Definition SimpleSetup.h:63
Implementation of OutputHandler that saves messages in a file.
Definition Console.h:126
Generic class to handle output from a piece of code.
Definition Console.h:103
PreSetupEvent plannerSwitch_
Event to be called when the evaluated planner is switched.
Definition Benchmark.h:288
std::function< void(const base::PlannerPtr &)> PreSetupEvent
Signature of function that can be called before a planner execution is started.
Definition Benchmark.h:79
Status status_
The current status of this benchmarking instance.
Definition Benchmark.h:285
const std::map< std::string, std::string > & getExperimentParameters() const
Get all optional benchmark parameters. The map key is 'name type'.
virtual void benchmark(const Request &req)
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
const Status & getStatus() const
Get the status of the benchmarking code. This function can be called in a separate thread to check ho...
void clearPlanners()
Clear the set of planners to be benchmarked.
std::vector< base::PlannerPtr > planners_
The set of planners to be tested.
Definition Benchmark.h:279
void setPreRunEvent(const PreSetupEvent &event)
Set the event to be called before the run of a planner.
PostSetupEvent postRun_
Event to be called after the run of a planner.
Definition Benchmark.h:294
const std::string & getExperimentName() const
Get the name of the experiment.
void setExperimentName(const std::string &name)
Set the name of the experiment.
void setPlannerSwitchEvent(const PreSetupEvent &event)
Set the event to be called before any runs of a particular planner (when the planner is switched).
CompleteExperiment exp_
The collected experimental data (for all planners).
Definition Benchmark.h:282
control::SimpleSetup * csetup_
The instance of the problem to benchmark (if planning with controls).
Definition Benchmark.h:276
std::function< void(const base::PlannerPtr &, RunProperties &)> PostSetupEvent
Signature of function that can be called after a planner execution is completed.
Definition Benchmark.h:82
void addPlanner(const base::PlannerPtr &planner)
Add a planner to use.
geometric::SimpleSetup * gsetup_
The instance of the problem to benchmark (if geometric planning).
Definition Benchmark.h:273
void setPostRunEvent(const PostSetupEvent &event)
Set the event to be called after the run of a planner.
void addPlannerAllocator(const base::PlannerAllocator &pa)
Add a planner allocator to use.
std::size_t numExperimentParameters() const
Return the number of optional benchmark parameters.
bool saveResultsToFile() const
Save the results of the benchmark to a file. The name of the file is the current date and time.
virtual bool saveResultsToStream(std::ostream &out=std::cout) const
Save the results of the benchmark to a stream.
const CompleteExperiment & getRecordedExperimentData() const
Return all the experiment data that would be written to the results file. The data should not be chan...
PreSetupEvent preRun_
Event to be called before the run of a planner.
Definition Benchmark.h:291
bool saveResultsToFile(const char *filename) const
Save the results of the benchmark to a file.
Benchmark(geometric::SimpleSetup &setup, const std::string &name=std::string())
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name...
void addExperimentParameter(const std::string &name, const std::string &type, const std::string &value)
Add an optional parameter's information to the benchmark output. Useful for aggregating results over ...
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition Console.h:68
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition Console.h:64
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition Console.h:66
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition Planner.h:428
std::function< bool()> PlannerTerminationConditionFn
Signature for functions that decide whether termination conditions have been met for a planner,...
MemUsage_t getProcessMemoryUsage()
Get the amount of memory the current process is using. This should work on major platforms (Windows,...
std::string getHostname()
Get the hostname of the machine in use.
std::string getCPUInfo()
Get information about the CPU of the machine in use.
unsigned long long MemUsage_t
Amount of memory used, in bytes.
OutputHandler * getOutputHandler()
Get the instance of the OutputHandler currently used. This is nullptr in case there is no output hand...
Definition Console.cpp:115
void useOutputHandler(OutputHandler *oh)
Specify the instance of the OutputHandler to use. By default, this is OutputHandlerSTD.
Definition Console.cpp:108
void noOutputHandler()
This function instructs ompl that no messages should be outputted. Equivalent to useOutputHandler(nul...
Definition Console.cpp:95
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition Time.h:52
point now()
Get the current time point.
Definition Time.h:58
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition Time.h:64
std::string as_string(const point &p)
Return string representation of point in time.
Definition Time.h:78
Includes various tools such as self config, benchmarking, etc.
Main namespace. Contains everything in this library.
std::string toString(float val)
convert float to string using classic "C" locale semantics
Definition String.cpp:82
A class to store the exit status of Planner::solve().
StatusType
The possible values of the status returned by a planner.
@ TYPE_COUNT
The number of possible status values.
std::string asString() const
Return a string representation.
This structure holds experimental data for a set of planners.
Definition Benchmark.h:112
Representation of a benchmark request.
Definition Benchmark.h:152
unsigned int runCount
the number of times to run each planner; 100 by default If set to 0, then run each planner as many ti...
Definition Benchmark.h:175
bool displayProgress
flag indicating whether progress is to be displayed or not; true by default
Definition Benchmark.h:182
double maxMem
the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default
Definition Benchmark.h:171
double timeBetweenUpdates
When collecting time-varying data from a planner during its execution, the planner's progress will be...
Definition Benchmark.h:179
bool saveConsoleOutput
flag indicating whether console output is saved (in an automatically generated filename); true by def...
Definition Benchmark.h:186
double maxTime
the maximum amount of time a planner is allowed to run (seconds); 5.0 by default
Definition Benchmark.h:168
bool simplify
flag indicating whether simplification should be applied to path; true by default
Definition Benchmark.h:189
The data collected from a run of a planner is stored as key-value pairs.
Definition Benchmark.h:73
This structure contains information about the activity of a benchmark instance. If the instance is ru...
Definition Benchmark.h:56