22#include "MotionBenchmakerDemo.h"
28#include <boost/program_options.hpp>
29#include <vamp/collision/shapes.hh>
30#include <vamp/collision/capt.hh>
31#include <vamp/collision/attachments.hh>
33namespace po = boost::program_options;
35int main(
int argc,
char **argv)
37 po::options_description desc(
"Options");
39 std::string problemFile;
40 std::string robotName;
41 std::string plannerName;
42 unsigned int benchmarkTrials = 0;
43 double timeoutSeconds = 5.0;
45 desc.add_options()(
"help",
"show help message")(
46 "problem-file", po::value<std::string>(&problemFile)->default_value(
"problems.json"),
47 "Problem file in JSON format")(
"robot", po::value<std::string>(&robotName)->default_value(
"panda"),
48 "Robot name (e.g., panda)")(
49 "planner", po::value<std::string>(&plannerName)->default_value(
"RRTConnect"),
50 "Planner name (e.g., RRTConnect, RRT, KPIECE1)")(
"benchmark",
51 po::value<unsigned int>(&benchmarkTrials)->default_value(0),
52 "Benchmark Planners for a specified number of trials")(
53 "timeout", po::value<double>(&timeoutSeconds)->default_value(5.0),
54 "Timeout in seconds for each planning attempt");
57 po::store(po::parse_command_line(argc, argv, desc), vm);
62 std::cout << desc << std::endl;
66 std::cout <<
"Motion Benchmaker Demo" << std::endl;
67 std::cout <<
"======================" << std::endl;
68 std::cout <<
"Problem File: " << problemFile << std::endl;
69 std::cout <<
"Robot: " << robotName << std::endl;
70 std::cout <<
"Planner: " << plannerName << std::endl;
71 std::cout <<
"Trials: " << benchmarkTrials << std::endl;
72 std::cout << std::endl;
80 const auto &problemNames = benchmarker.getProblemNames();
81 std::cout <<
"Available problems: ";
82 for (
size_t i = 0; i < problemNames.size(); ++i)
86 std::cout << problemNames[i];
88 std::cout << std::endl << std::endl;
91 std::cout <<
"Running benchmarks..." << std::endl;
92 auto results = benchmarker.benchmarkAll(benchmarkTrials, timeoutSeconds,
true);
95 if (benchmarkTrials > 0)
97 std::cout <<
"Benchmark Results Saved, use python script to transfer to .db" << std::endl;
101 for (
const auto &[problemName, problemResults] : results)
107 catch (
const std::exception &e)
109 std::cerr <<
"Error: " << e.what() << std::endl;
Configuration for running Motion Benchmark Maker benchmarks with OMPL and VAMP.
static void printStatistics(const std::string &problemName, const std::vector< PlanningResult > &results)
Print summary statistics for a set of results.