Robowflex  v0.1
Making MoveIt Easy
robowflex::OMPLPlanDataSetOutputter Class Reference

Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics.py is available in your PATH variable, the results are also compiled into a database file. More...

#include <benchmarking.h>

+ Inheritance diagram for robowflex::OMPLPlanDataSetOutputter:

Public Member Functions

 OMPLPlanDataSetOutputter (const std::string &prefix)
 Constructor. More...
 
 ~OMPLPlanDataSetOutputter () override
 Destructor, runs ompl_benchmark_statistics.py to generate benchmarking database. More...
 
void dump (const PlanDataSet &results) override
 Dumps results into a OMPL benchmarking log file in prefix_ named after the request name_. More...
 
- Public Member Functions inherited from robowflex::PlanDataSetOutputter
virtual ~PlanDataSetOutputter ()=default
 Virtual destructor for cleaning up resources. More...
 

Private Attributes

const std::string prefix_
 Log file prefix. More...
 

Detailed Description

Benchmark outputter that saves results into OMPL benchmarking log files. If ompl_benchmark_statistics.py is available in your PATH variable, the results are also compiled into a database file.

Definition at line 571 of file benchmarking.h.

Constructor & Destructor Documentation

◆ OMPLPlanDataSetOutputter()

OMPLPlanDataSetOutputter::OMPLPlanDataSetOutputter ( const std::string prefix)

Constructor.

Parameters
[in]prefixPrefix to place in front of all log files generated.
[in]dumpSceneIf true, will output scene into log file.

OMPLPlanDataSetOutputter

Definition at line 603 of file benchmarking.cpp.

603  : prefix_(prefix)
604 {
605 }
const std::string prefix_
Log file prefix.
Definition: benchmarking.h:591

◆ ~OMPLPlanDataSetOutputter()

OMPLPlanDataSetOutputter::~OMPLPlanDataSetOutputter ( )
override

Destructor, runs ompl_benchmark_statistics.py to generate benchmarking database.

Definition at line 607 of file benchmarking.cpp.

608 {
609 }

Member Function Documentation

◆ dump()

void OMPLPlanDataSetOutputter::dump ( const PlanDataSet results)
overridevirtual

Dumps results into a OMPL benchmarking log file in prefix_ named after the request name_.

Parameters
[in]resultsResults to dump to file.

Implements robowflex::PlanDataSetOutputter.

Definition at line 611 of file benchmarking.cpp.

612 {
613  std::ofstream out;
614  IO::createFile(out, log::format("%1%_%2%.log", prefix_, results.name));
615 
616  out << "MoveIt! version " << MOVEIT_VERSION << std::endl; // version
617  out << "Experiment " << results.name << std::endl; // experiment
618  out << "Running on " << IO::getHostname() << std::endl; // hostname
619  out << "Starting at " << results.start << std::endl; // date
620 
621  out << "<<<|" << std::endl;
622  out << "|>>>" << std::endl;
623 
624  // random seed (fake)
625  out << "0 is the random seed" << std::endl;
626 
627  // time limit
628  out << results.allowed_time << " seconds per run" << std::endl;
629 
630  // memory limit
631  out << "-1 MB per run" << std::endl;
632 
633  // num_runs
634  // out << results.data.size() << " runs per planner" << std::endl;
635 
636  // total_time
637  out << results.time << " seconds spent to collect the data" << std::endl;
638 
639  // num_enums / enums
640  out << "0 enum types" << std::endl;
641 
642  // num_planners
643  out << results.query_names.size() << " planners" << std::endl;
644 
645  // planners_data -> planner_data
646  for (const auto &name : results.query_names)
647  {
648  const auto &runs = results.data.find(name)->second;
649 
650  out << name << std::endl; // planner_name
651  out << "0 common properties" << std::endl;
652 
653  out << (runs[0]->metrics.size() + 2) << " properties for each run" << std::endl; // run_properties
654  out << "time REAL" << std::endl;
655  out << "success BOOLEAN" << std::endl;
656 
658  for (const auto &metric : runs[0]->metrics)
659  {
660  class ToString : public boost::static_visitor<const std::string>
661  {
662  public:
663  std::string operator()(int /* dummy */) const
664  {
665  return "INT";
666  }
667 
668  std::string operator()(std::size_t /* dummy */) const
669  {
670  return "BIGINT";
671  }
672 
673  std::string operator()(double /* dummy */) const
674  {
675  return "REAL";
676  }
677 
678  std::string operator()(bool /* dummy */) const
679  {
680  return "BOOLEAN";
681  }
682 
683  const std::string operator()(std::string /* dummy */) const
684  {
685  return "VARCHAR(128)";
686  }
687  };
688 
689  const auto &name = metric.first;
690  keys.emplace_back(name);
691 
692  out << name << " " << boost::apply_visitor(ToString(), metric.second) << std::endl;
693  }
694 
695  out << runs.size() << " runs" << std::endl;
696 
697  for (const auto &run : runs)
698  {
699  out << run->time << "; " //
700  << run->success << "; ";
701 
702  for (const auto &key : keys)
703  out << toMetricString(run->metrics.find(key)->second) << "; ";
704 
705  out << std::endl;
706  }
707 
708  const auto &progress_names = runs[0]->property_names;
709  if (not progress_names.empty())
710  {
711  out << progress_names.size() << " progress properties for each run" << std::endl;
712  for (const auto &name : progress_names)
713  out << name << std::endl;
714 
715  out << runs.size() << " runs" << std::endl;
716  for (const auto &run : runs)
717  {
718  for (const auto &point : run->progress)
719  {
720  for (const auto &name : progress_names)
721  {
722  auto it = point.find(name);
723  out << it->second << ",";
724  }
725 
726  out << ";";
727  }
728 
729  out << std::endl;
730  }
731  }
732 
733  out << "." << std::endl;
734  }
735 
736  out.close();
737 }
std::map< std::string, std::vector< PlanDataPtr > > data
Map of query name to collected data.
Definition: benchmarking.h:177
boost::posix_time::ptime start
Start time of dataset computation.
Definition: benchmarking.h:147
std::vector< std::string > query_names
All unique names used by planning queries.
Definition: benchmarking.h:168
double allowed_time
Allowed planning time used per query.
Definition: benchmarking.h:155
std::string name
Name of this dataset.
Definition: benchmarking.h:167
double time
Total computation time for entire dataset.
Definition: benchmarking.h:146
T close(T... args)
T emplace_back(T... args)
T endl(T... args)
std::string getHostname()
Get the hostname of the system.
void createFile(std::ofstream &out, const std::string &file)
Creates a file and opens an output stream. Creates directories if they do not exist.
std::string format(const std::string &fmt, Args &&... args)
Recursion base case, return string form of formatted arguments.
Definition: log.h:60
std::string toMetricString(const PlannerMetric &metric)
Convert a planner metric into a string.
T size(T... args)

Member Data Documentation

◆ prefix_

const std::string robowflex::OMPLPlanDataSetOutputter::prefix_
private

Log file prefix.

Definition at line 591 of file benchmarking.h.


The documentation for this class was generated from the following files: