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 
50 namespace 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  collectProgressProperties(planner->getPlannerProgressProperties(), timeBetweenUpdates);
132  }));
133  status_ = planner->solve(ptc, 0.1);
134  solvedFlag_.lock();
135  solved_ = true;
136  solvedCondition_.notify_all();
137  solvedFlag_.unlock();
138  if (t)
139  t->join(); // maybe look into interrupting even if planner throws an exception
140  }
141  catch (std::runtime_error &e)
142  {
143  std::stringstream es;
144  es << "There was an error executing planner " << benchmark_->getStatus().activePlanner
145  << ", run = " << benchmark_->getStatus().activeRun << std::endl;
146  es << "*** " << e.what() << std::endl;
147  std::cerr << es.str();
148  OMPL_ERROR(es.str().c_str());
149  }
150 
151  timeUsed_ = time::seconds(time::now() - timeStart);
152  memUsed_ = machine::getProcessMemoryUsage();
153  }
154 
155  void collectProgressProperties(const base::Planner::PlannerProgressProperties &properties,
156  const time::duration &timePerUpdate)
157  {
158  time::point timeStart = time::now();
159 
160  std::unique_lock<std::mutex> ulock(solvedFlag_);
161  while (!solved_)
162  {
163  if (solvedCondition_.wait_for(ulock, timePerUpdate) == std::cv_status::no_timeout)
164  return;
165  else
166  {
167  double timeInSeconds = time::seconds(time::now() - timeStart);
168  std::string timeStamp = ompl::toString(timeInSeconds);
169  std::map<std::string, std::string> data;
170  data["time REAL"] = timeStamp;
171  for (const auto &property : properties)
172  {
173  data[property.first] = property.second();
174  }
175  runProgressData_.push_back(data);
176  }
177  }
178  }
179 
180  const Benchmark *benchmark_;
181  double timeUsed_;
182  machine::MemUsage_t memUsed_;
183  base::PlannerStatus status_;
184  Benchmark::RunProgressData runProgressData_;
185 
186  // variables needed for progress property collection
187  bool solved_;
188  std::mutex solvedFlag_;
189  std::condition_variable solvedCondition_;
190  };
191  } // namespace tools
192 } // namespace ompl
194 
196  : gsetup_(&setup), csetup_(nullptr)
197 {
198  exp_.name = name;
199 }
200 
202  : gsetup_(nullptr), csetup_(&setup)
203 {
204  exp_.name = name;
205 }
206 
207 void ompl::tools::Benchmark::addExperimentParameter(const std::string &name, const std::string &type,
208  const std::string &value)
209 {
210  exp_.parameters[name + " " + type] = value;
211 }
212 
213 const std::map<std::string, std::string> &ompl::tools::Benchmark::getExperimentParameters() const
214 {
215  return exp_.parameters;
216 }
217 
219 {
220  return exp_.parameters.size();
221 }
222 
223 void ompl::tools::Benchmark::setExperimentName(const std::string &name)
224 {
225  exp_.name = name;
226 }
227 
229 {
230  return exp_.name;
231 }
232 
233 void ompl::tools::Benchmark::addPlanner(const base::PlannerPtr &planner)
234 {
235  if (planner && planner->getSpaceInformation().get() != (gsetup_ != nullptr ? gsetup_->getSpaceInformation().get() :
236  csetup_->getSpaceInformation().get()))
237  throw Exception("Planner instance does not match space information");
238  planners_.push_back(planner);
239 }
240 
242 {
243  planners_.push_back(pa(gsetup_ != nullptr ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation()));
244 }
245 
247 {
248  planners_.clear();
249 }
250 
252 {
253  plannerSwitch_ = event;
254 }
255 
258 {
259  preRun_ = event;
260 }
261 
264 {
265  postRun_ = event;
266 }
267 
269 {
270  return status_;
271 }
272 
274 {
275  return exp_;
276 }
277 
278 bool ompl::tools::Benchmark::saveResultsToFile(const char *filename) const
279 {
280  bool result = false;
281 
282  std::ofstream fout(filename);
283  if (fout.good())
284  {
285  result = saveResultsToStream(fout);
286  OMPL_INFORM("Results saved to '%s'", filename);
287  }
288  else
289  {
290  // try to save to a different file, if we can
291  if (getResultsFilename(exp_) != std::string(filename))
292  result = saveResultsToFile();
293 
294  OMPL_ERROR("Unable to write results to '%s'", filename);
295  }
296  return result;
297 }
298 
300 {
301  std::string filename = getResultsFilename(exp_);
302  return saveResultsToFile(filename.c_str());
303 }
304 
305 bool ompl::tools::Benchmark::saveResultsToStream(std::ostream &out) const
306 {
307  if (exp_.planners.empty())
308  {
309  OMPL_WARN("There is no experimental data to save");
310  return false;
311  }
312 
313  if (!out.good())
314  {
315  OMPL_ERROR("Unable to write to stream");
316  return false;
317  }
318 
319  out << "OMPL version " << OMPL_VERSION << std::endl;
320  out << "Experiment " << (exp_.name.empty() ? "NO_NAME" : exp_.name) << std::endl;
321 
322  out << exp_.parameters.size() << " experiment properties" << std::endl;
323  for (const auto &parameter : exp_.parameters)
324  out << parameter.first << " = " << parameter.second << std::endl;
325 
326  out << "Running on " << (exp_.host.empty() ? "UNKNOWN" : exp_.host) << std::endl;
327  out << "Starting at " << time::as_string(exp_.startTime) << std::endl;
328  out << "<<<|" << std::endl << exp_.setupInfo << "|>>>" << std::endl;
329  out << "<<<|" << std::endl << exp_.cpuInfo << "|>>>" << std::endl;
330 
331  out << exp_.seed << " is the random seed" << std::endl;
332  out << exp_.maxTime << " seconds per run" << std::endl;
333  out << exp_.maxMem << " MB per run" << std::endl;
334  out << exp_.runCount << " runs per planner" << std::endl;
335  out << exp_.totalDuration << " seconds spent to collect the data" << std::endl;
336 
337  // change this if more enum types are added
338  out << "1 enum type" << std::endl;
339  out << "status";
340  for (unsigned int i = 0; i < base::PlannerStatus::TYPE_COUNT; ++i)
341  out << '|' << base::PlannerStatus(static_cast<base::PlannerStatus::StatusType>(i)).asString();
342  out << std::endl;
343 
344  out << exp_.planners.size() << " planners" << std::endl;
345 
346  for (const auto &planner : exp_.planners)
347  {
348  out << planner.name << std::endl;
349 
350  // get names of common properties
351  std::vector<std::string> properties;
352  for (auto &property : planner.common)
353  properties.push_back(property.first);
354  std::sort(properties.begin(), properties.end());
355 
356  // print names & values of common properties
357  out << properties.size() << " common properties" << std::endl;
358  for (auto &property : properties)
359  {
360  auto it = planner.common.find(property);
361  out << it->first << " = " << it->second << std::endl;
362  }
363 
364  // construct the list of all possible properties for all runs
365  std::map<std::string, bool> propSeen;
366  for (auto &run : planner.runs)
367  for (auto &property : run)
368  propSeen[property.first] = true;
369 
370  properties.clear();
371 
372  for (auto &it : propSeen)
373  properties.push_back(it.first);
374  std::sort(properties.begin(), properties.end());
375 
376  // print the property names
377  out << properties.size() << " properties for each run" << std::endl;
378  for (auto &property : properties)
379  out << property << std::endl;
380 
381  // print the data for each run
382  out << planner.runs.size() << " runs" << std::endl;
383  for (auto &run : planner.runs)
384  {
385  for (auto &property : properties)
386  {
387  auto it = run.find(property);
388  if (it != run.end())
389  out << it->second;
390  out << "; ";
391  }
392  out << std::endl;
393  }
394 
395  // print the run progress data if it was reported
396  if (planner.runsProgressData.size() > 0)
397  {
398  // Print number of progress properties
399  out << planner.progressPropertyNames.size() << " progress properties for each run" << std::endl;
400  // Print progress property names
401  for (const auto &progPropName : planner.progressPropertyNames)
402  {
403  out << progPropName << std::endl;
404  }
405  // Print progress properties for each run
406  out << planner.runsProgressData.size() << " runs" << std::endl;
407  for (const auto &r : planner.runsProgressData)
408  {
409  // For each time point
410  for (const auto &t : r)
411  {
412  // Print each of the properties at that time point
413  for (const auto &iter : t)
414  {
415  out << iter.second << ",";
416  }
417 
418  // Separate time points by semicolons
419  out << ";";
420  }
421 
422  // Separate runs by newlines
423  out << std::endl;
424  }
425  }
426 
427  out << '.' << std::endl;
428  }
429  return true;
430 }
431 
433 {
434  // sanity checks
435  if (gsetup_)
436  {
437  if (!gsetup_->getSpaceInformation()->isSetup())
438  gsetup_->getSpaceInformation()->setup();
439  }
440  else
441  {
442  if (!csetup_->getSpaceInformation()->isSetup())
443  csetup_->getSpaceInformation()->setup();
444  }
445 
446  if (!(gsetup_ ? gsetup_->getGoal() : csetup_->getGoal()))
447  {
448  OMPL_ERROR("No goal defined");
449  return;
450  }
451 
452  if (planners_.empty())
453  {
454  OMPL_ERROR("There are no planners to benchmark");
455  return;
456  }
457 
458  status_.running = true;
459  exp_.totalDuration = 0.0;
460  exp_.maxTime = req.maxTime;
461  exp_.maxMem = req.maxMem;
462  exp_.runCount = req.runCount;
463  exp_.host = machine::getHostname();
464  exp_.cpuInfo = machine::getCPUInfo();
465  exp_.seed = RNG::getSeed();
466 
467  exp_.startTime = time::now();
468 
469  OMPL_INFORM("Configuring planners ...");
470 
471  // clear previous experimental data
472  exp_.planners.clear();
473  exp_.planners.resize(planners_.size());
474 
475  const base::ProblemDefinitionPtr &pdef =
476  gsetup_ ? gsetup_->getProblemDefinition() : csetup_->getProblemDefinition();
477  // set up all the planners
478  for (unsigned int i = 0; i < planners_.size(); ++i)
479  {
480  // configure the planner
481  planners_[i]->setProblemDefinition(pdef);
482  if (!planners_[i]->isSetup())
483  planners_[i]->setup();
484  exp_.planners[i].name = (gsetup_ ? "geometric_" : "control_") + planners_[i]->getName();
485  OMPL_INFORM("Configured %s", exp_.planners[i].name.c_str());
486  }
487 
488  OMPL_INFORM("Done configuring planners.");
489  OMPL_INFORM("Saving planner setup information ...");
490 
491  std::stringstream setupInfo;
492  if (gsetup_)
493  gsetup_->print(setupInfo);
494  else
495  csetup_->print(setupInfo);
496  setupInfo << std::endl << "Properties of benchmarked planners:" << std::endl;
497  for (auto &planner : planners_)
498  planner->printProperties(setupInfo);
499 
500  exp_.setupInfo = setupInfo.str();
501 
502  OMPL_INFORM("Done saving information");
503 
504  OMPL_INFORM("Beginning benchmark");
506  boost::scoped_ptr<msg::OutputHandlerFile> ohf;
507  if (req.saveConsoleOutput)
508  {
509  ohf.reset(new msg::OutputHandlerFile(getConsoleFilename(exp_).c_str()));
510  msg::useOutputHandler(ohf.get());
511  }
512  else
514  OMPL_INFORM("Beginning benchmark");
515 
516  boost::scoped_ptr<ompl::time::ProgressDisplay> progress;
517  if (req.displayProgress)
518  {
519  std::cout << "Running experiment " << exp_.name << "." << std::endl;
520  if (req.runCount)
521  std::cout << "Each planner will be executed " << req.runCount << " times for at most " << req.maxTime
522  << " seconds.";
523  else
524  std::cout << "Each planner will be executed as many times as possible within " << req.maxTime
525  << " seconds.";
526  std::cout << " Memory is limited at " << req.maxMem << "MB." << std::endl;
527  progress.reset(new ompl::time::ProgressDisplay);
528  }
529 
531  auto maxMemBytes = (machine::MemUsage_t)(req.maxMem * 1024 * 1024);
532 
533  for (unsigned int i = 0; i < planners_.size(); ++i)
534  {
535  status_.activePlanner = exp_.planners[i].name;
536  // execute planner switch event, if set
537  try
538  {
539  if (plannerSwitch_)
540  {
541  OMPL_INFORM("Executing planner-switch event for planner %s ...", status_.activePlanner.c_str());
542  plannerSwitch_(planners_[i]);
543  OMPL_INFORM("Completed execution of planner-switch event");
544  }
545  }
546  catch (std::runtime_error &e)
547  {
548  std::stringstream es;
549  es << "There was an error executing the planner-switch event for planner " << status_.activePlanner
550  << std::endl;
551  es << "*** " << e.what() << std::endl;
552  std::cerr << es.str();
553  OMPL_ERROR(es.str().c_str());
554  }
555  if (gsetup_)
556  gsetup_->setup();
557  else
558  csetup_->setup();
559  planners_[i]->params().getParams(exp_.planners[i].common);
560  planners_[i]->getSpaceInformation()->params().getParams(exp_.planners[i].common);
561 
562  // Add planner progress property names to struct
563  exp_.planners[i].progressPropertyNames.emplace_back("time REAL");
564  for (const auto &property : planners_[i]->getPlannerProgressProperties())
565  {
566  exp_.planners[i].progressPropertyNames.push_back(property.first);
567  }
568  std::sort(exp_.planners[i].progressPropertyNames.begin(), exp_.planners[i].progressPropertyNames.end());
569 
570  // run the planner
571  double maxTime = req.maxTime;
572  unsigned int j = 0;
573  while (true)
574  {
575  status_.activeRun = j;
576  status_.progressPercentage =
577  req.runCount ? (double)(100 * (req.runCount * i + j)) / (double)(planners_.size() * req.runCount) :
578  (double)(100 * i) / (double)(planners_.size());
579 
580  if (req.displayProgress)
581  while (status_.progressPercentage > progress->count())
582  ++(*progress);
583 
584  OMPL_INFORM("Preparing for run %d of %s", status_.activeRun, status_.activePlanner.c_str());
585 
586  // make sure all planning data structures are cleared
587  try
588  {
589  planners_[i]->clear();
590  if (gsetup_)
591  {
592  gsetup_->getProblemDefinition()->clearSolutionPaths();
593  gsetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
594  }
595  else
596  {
597  csetup_->getProblemDefinition()->clearSolutionPaths();
598  csetup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
599  }
600  }
601  catch (std::runtime_error &e)
602  {
603  std::stringstream es;
604  es << "There was an error while preparing for run " << status_.activeRun << " of planner "
605  << status_.activePlanner << std::endl;
606  es << "*** " << e.what() << std::endl;
607  std::cerr << es.str();
608  OMPL_ERROR(es.str().c_str());
609  }
610 
611  // execute pre-run event, if set
612  try
613  {
614  if (preRun_)
615  {
616  OMPL_INFORM("Executing pre-run event for run %d of planner %s ...", status_.activeRun,
617  status_.activePlanner.c_str());
618  preRun_(planners_[i]);
619  OMPL_INFORM("Completed execution of pre-run event");
620  }
621  }
622  catch (std::runtime_error &e)
623  {
624  std::stringstream es;
625  es << "There was an error executing the pre-run event for run " << status_.activeRun << " of planner "
626  << status_.activePlanner << std::endl;
627  es << "*** " << e.what() << std::endl;
628  std::cerr << es.str();
629  OMPL_ERROR(es.str().c_str());
630  }
631 
632  RunPlanner rp(this);
633  rp.run(planners_[i], memStart, maxMemBytes, maxTime, req.timeBetweenUpdates);
634  bool solved = gsetup_ ? gsetup_->haveSolutionPath() : csetup_->haveSolutionPath();
635 
636  // store results
637  try
638  {
639  RunProperties run;
640 
641  run["time REAL"] = ompl::toString(rp.getTimeUsed());
642  run["memory REAL"] = ompl::toString((double)rp.getMemUsed() / (1024.0 * 1024.0));
643  run["status ENUM"] = std::to_string((int)static_cast<base::PlannerStatus::StatusType>(rp.getStatus()));
644  if (gsetup_)
645  {
646  run["solved BOOLEAN"] = std::to_string(gsetup_->haveExactSolutionPath());
647  run["valid segment fraction REAL"] =
648  ompl::toString(gsetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());
649  }
650  else
651  {
652  run["solved BOOLEAN"] = std::to_string(csetup_->haveExactSolutionPath());
653  run["valid segment fraction REAL"] =
654  ompl::toString(csetup_->getSpaceInformation()->getMotionValidator()->getValidMotionFraction());
655  }
656 
657  if (solved)
658  {
659  if (gsetup_)
660  {
661  run["approximate solution BOOLEAN"] =
662  std::to_string(gsetup_->getProblemDefinition()->hasApproximateSolution());
663  run["solution difference REAL"] =
664  ompl::toString(gsetup_->getProblemDefinition()->getSolutionDifference());
665  run["solution length REAL"] = ompl::toString(gsetup_->getSolutionPath().length());
666  run["solution smoothness REAL"] = ompl::toString(gsetup_->getSolutionPath().smoothness());
667  run["solution clearance REAL"] = ompl::toString(gsetup_->getSolutionPath().clearance());
668  run["solution segments INTEGER"] =
669  std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);
670  run["correct solution BOOLEAN"] = std::to_string(gsetup_->getSolutionPath().check());
671 
672  unsigned int factor = gsetup_->getStateSpace()->getValidSegmentCountFactor();
673  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);
674  run["correct solution strict BOOLEAN"] = std::to_string(gsetup_->getSolutionPath().check());
675  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);
676 
677  if (req.simplify)
678  {
679  // simplify solution
680  time::point timeStart = time::now();
681  gsetup_->simplifySolution();
682  double timeUsed = time::seconds(time::now() - timeStart);
683  run["simplification time REAL"] = ompl::toString(timeUsed);
684  run["simplified solution length REAL"] =
685  ompl::toString(gsetup_->getSolutionPath().length());
686  run["simplified solution smoothness REAL"] =
687  ompl::toString(gsetup_->getSolutionPath().smoothness());
688  run["simplified solution clearance REAL"] =
689  ompl::toString(gsetup_->getSolutionPath().clearance());
690  run["simplified solution segments INTEGER"] =
691  std::to_string(gsetup_->getSolutionPath().getStateCount() - 1);
692  run["simplified correct solution BOOLEAN"] =
693  std::to_string(gsetup_->getSolutionPath().check());
694  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor * 4);
695  run["simplified correct solution strict BOOLEAN"] =
696  std::to_string(gsetup_->getSolutionPath().check());
697  gsetup_->getStateSpace()->setValidSegmentCountFactor(factor);
698  }
699  }
700  else
701  {
702  run["approximate solution BOOLEAN"] =
703  std::to_string(csetup_->getProblemDefinition()->hasApproximateSolution());
704  run["solution difference REAL"] =
705  ompl::toString(csetup_->getProblemDefinition()->getSolutionDifference());
706  run["solution length REAL"] = ompl::toString(csetup_->getSolutionPath().length());
707  run["solution clearance REAL"] =
708  ompl::toString(csetup_->getSolutionPath().asGeometric().clearance());
709  run["solution segments INTEGER"] = std::to_string(csetup_->getSolutionPath().getControlCount());
710  run["correct solution BOOLEAN"] = std::to_string(csetup_->getSolutionPath().check());
711  }
712  }
713 
714  base::PlannerData pd(gsetup_ ? gsetup_->getSpaceInformation() : csetup_->getSpaceInformation());
715  planners_[i]->getPlannerData(pd);
716  run["graph states INTEGER"] = std::to_string(pd.numVertices());
717  run["graph motions INTEGER"] = std::to_string(pd.numEdges());
718 
719  for (const auto &prop : pd.properties)
720  run[prop.first] = prop.second;
721 
722  // execute post-run event, if set
723  try
724  {
725  if (postRun_)
726  {
727  OMPL_INFORM("Executing post-run event for run %d of planner %s ...", status_.activeRun,
728  status_.activePlanner.c_str());
729  postRun_(planners_[i], run);
730  OMPL_INFORM("Completed execution of post-run event");
731  }
732  }
733  catch (std::runtime_error &e)
734  {
735  std::stringstream es;
736  es << "There was an error in the execution of the post-run event for run " << status_.activeRun
737  << " of planner " << status_.activePlanner << std::endl;
738  es << "*** " << e.what() << std::endl;
739  std::cerr << es.str();
740  OMPL_ERROR(es.str().c_str());
741  }
742 
743  exp_.planners[i].runs.push_back(run);
744 
745  // Add planner progress data from the planner progress
746  // collector if there was anything to report
747  if (planners_[i]->getPlannerProgressProperties().size() > 0)
748  {
749  exp_.planners[i].runsProgressData.push_back(rp.getRunProgressData());
750  }
751  }
752  catch (std::runtime_error &e)
753  {
754  std::stringstream es;
755  es << "There was an error in the extraction of planner results: planner = " << status_.activePlanner
756  << ", run = " << status_.activePlanner << std::endl;
757  es << "*** " << e.what() << std::endl;
758  std::cerr << es.str();
759  OMPL_ERROR(es.str().c_str());
760  }
761 
762  ++j;
763  if (req.runCount == 0)
764  {
765  maxTime -= rp.getTimeUsed();
766  if (maxTime < 0.)
767  break;
768  }
769  else
770  {
771  if (j >= req.runCount)
772  break;
773  }
774  }
775  planners_[i]->clear();
776  }
777 
778  status_.running = false;
779  status_.progressPercentage = 100.0;
780  if (req.displayProgress)
781  {
782  while (status_.progressPercentage > progress->count())
783  ++(*progress);
784  std::cout << std::endl;
785  }
786 
787  exp_.totalDuration = time::seconds(time::now() - exp_.startTime);
788 
789  OMPL_INFORM("Benchmark complete");
791  OMPL_INFORM("Benchmark complete");
792 }
std::string name
The name of the experiment.
Definition: Benchmark.h:210
void setPreRunEvent(const PreSetupEvent &event)
Set the event to be called before the run of a planner.
Definition: Benchmark.cpp:257
void setPlannerSwitchEvent(const PreSetupEvent &event)
Set the event to be called before any runs of a particular planner (when the planner is switched)
Definition: Benchmark.cpp:251
std::function< bool()> PlannerTerminationConditionFn
Signature for functions that decide whether termination conditions have been met for a planner,...
std::function< void(const base::PlannerPtr &, RunProperties &)> PostSetupEvent
Signature of function that can be called after a planner execution is completed.
Definition: Benchmark.h:178
std::chrono::system_clock::time_point point
Representation of a point in time.
Definition: Time.h:116
std::string getHostname()
Get the hostname of the machine in use.
MemUsage_t getProcessMemoryUsage()
Get the amount of memory the current process is using. This should work on major platforms (Windows,...
const std::string & getExperimentName() const
Get the name of the experiment.
Definition: Benchmark.cpp:228
void noOutputHandler()
This function instructs ompl that no messages should be outputted. Equivalent to useOutputHandler(nul...
Definition: Console.cpp:95
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:417
Generic class to handle output from a piece of code.
Definition: Console.h:102
void useOutputHandler(OutputHandler *oh)
Specify the instance of the OutputHandler to use. By default, this is OutputHandlerSTD.
Definition: Console.cpp:108
unsigned long long MemUsage_t
Amount of memory used, in bytes.
Definition: MachineSpecs.h:112
Create the set of classes typically needed to solve a geometric problem.
Definition: SimpleSetup.h:126
CompleteExperiment exp_
The collected experimental data (for all planners)
Definition: Benchmark.h:378
std::string asString() const
Return a string representation.
@ TYPE_COUNT
The number of possible status values.
point now()
Get the current time point.
Definition: Time.h:122
unsigned int numEdges() const
Retrieve the number of edges in this structure.
#define OMPL_INFORM(fmt,...)
Log a formatted information string.
Definition: Console.h:68
This structure holds experimental data for a set of planners.
Definition: Benchmark.h:207
void clearPlanners()
Clear the set of planners to be benchmarked.
Definition: Benchmark.cpp:246
const std::map< std::string, std::string > & getExperimentParameters() const
Get all optional benchmark parameters. The map key is 'name type'
Definition: Benchmark.cpp:213
bool simplify
flag indicating whether simplification should be applied to path; true by default
Definition: Benchmark.h:285
Object containing planner generated vertex and edge data. It is assumed that all vertices are unique,...
Definition: PlannerData.h:238
const CompleteExperiment & getRecordedExperimentData() const
Return all the experiment data that would be written to the results file. The data should not be chan...
Definition: Benchmark.cpp:273
void addPlannerAllocator(const base::PlannerAllocator &pa)
Add a planner allocator to use.
Definition: Benchmark.cpp:241
void addPlanner(const base::PlannerPtr &planner)
Add a planner to use.
Definition: Benchmark.cpp:233
std::function< void(const base::PlannerPtr &)> PreSetupEvent
Signature of function that can be called before a planner execution is started.
Definition: Benchmark.h:175
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:271
void setExperimentName(const std::string &name)
Set the name of the experiment.
Definition: Benchmark.cpp:223
bool saveConsoleOutput
flag indicating whether console output is saved (in an automatically generated filename); true by def...
Definition: Benchmark.h:282
unsigned int numVertices() const
Retrieve the number of vertices in this structure.
Create the set of classes typically needed to solve a control problem.
Definition: SimpleSetup.h:126
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 ...
Definition: Benchmark.cpp:207
bool displayProgress
flag indicating whether progress is to be displayed or not; true by default
Definition: Benchmark.h:278
bool saveResultsToFile() const
Save the results of the benchmark to a file. The name of the file is the current date and time.
Definition: Benchmark.cpp:299
A class to store the exit status of Planner::solve()
std::function< PlannerPtr(const SpaceInformationPtr &)> PlannerAllocator
Definition of a function that can allocate a planner.
Definition: Planner.h:501
Representation of a benchmark request.
Definition: Benchmark.h:247
Implementation of OutputHandler that saves messages in a file.
Definition: Console.h:125
static std::uint_fast32_t getSeed()
Get the seed used to generate the seeds of each RNG instance. Passing the returned value to setSeed()...
std::chrono::system_clock::duration duration
Representation of a time duration.
Definition: Time.h:119
std::size_t numExperimentParameters() const
Return the number of optional benchmark parameters.
Definition: Benchmark.cpp:218
#define OMPL_WARN(fmt,...)
Log a formatted warning string.
Definition: Console.h:66
std::map< std::string, std::string > properties
Any extra properties (key-value pairs) the planner can set.
Definition: PlannerData.h:474
virtual void benchmark(const Request &req)
Benchmark the added planners on the defined problem. Repeated calls clear previously gathered data.
Definition: Benchmark.cpp:432
std::string getCPUInfo()
Get information about the CPU of the machine in use.
Benchmark(geometric::SimpleSetup &setup, const std::string &name=std::string())
Constructor needs the SimpleSetup instance needed for planning. Optionally, the experiment name (name...
Definition: Benchmark.cpp:195
StatusType
The possible values of the status returned by a planner.
The data collected from a run of a planner is stored as key-value pairs.
Definition: Benchmark.h:168
double maxMem
the maximum amount of memory a planner is allowed to use (MB); 4096.0 by default
Definition: Benchmark.h:267
#define OMPL_ERROR(fmt,...)
Log a formatted error string.
Definition: Console.h:64
std::string as_string(const point &p)
Return string representation of point in time.
Definition: Time.h:142
void setPostRunEvent(const PostSetupEvent &event)
Set the event to be called after the run of a planner.
Definition: Benchmark.cpp:263
The exception type for ompl.
Definition: Exception.h:78
const Status & getStatus() const
Get the status of the benchmarking code. This function can be called in a separate thread to check ho...
Definition: Benchmark.cpp:268
OutputHandler * getOutputHandler()
Get the instance of the OutputHandler currently used. This is nullptr in case there is no output hand...
Definition: Console.cpp:115
std::string toString(float val)
convert float to string using classic "C" locale semantics
Definition: String.cpp:82
This structure contains information about the activity of a benchmark instance. If the instance is ru...
Definition: Benchmark.h:151
duration seconds(double sec)
Return the time duration representing a given number of seconds.
Definition: Time.h:128
virtual bool saveResultsToStream(std::ostream &out=std::cout) const
Save the results of the benchmark to a stream.
Definition: Benchmark.cpp:305
double timeBetweenUpdates
When collecting time-varying data from a planner during its execution, the planner's progress will be...
Definition: Benchmark.h:275
Main namespace. Contains everything in this library.
double maxTime
the maximum amount of time a planner is allowed to run (seconds); 5.0 by default
Definition: Benchmark.h:264