Loading...
Searching...
No Matches
MotionBenchmakerDemoMain.cpp
Go to the documentation of this file.
1
21
22#include "MotionBenchmakerDemo.h"
23#include <iostream>
24#include <string>
25
26#include <vector>
27#include <optional>
28#include <boost/program_options.hpp>
29#include <vamp/collision/shapes.hh>
30#include <vamp/collision/capt.hh>
31#include <vamp/collision/attachments.hh>
32
33namespace po = boost::program_options;
34
35int main(int argc, char **argv)
36{
37 po::options_description desc("Options");
38
39 std::string problemFile;
40 std::string robotName;
41 std::string plannerName;
42 unsigned int benchmarkTrials = 0;
43 double timeoutSeconds = 5.0;
44
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");
55
56 po::variables_map vm;
57 po::store(po::parse_command_line(argc, argv, desc), vm);
58 po::notify(vm);
59
60 if (vm.count("help"))
61 {
62 std::cout << desc << std::endl;
63 return 0;
64 }
65
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;
73
74 try
75 {
76 // Create the benchmarker
77 MotionBenchmakerDemo benchmarker(robotName, problemFile, plannerName);
78
79 // Get list of problems
80 const auto &problemNames = benchmarker.getProblemNames();
81 std::cout << "Available problems: ";
82 for (size_t i = 0; i < problemNames.size(); ++i)
83 {
84 if (i > 0)
85 std::cout << ", ";
86 std::cout << problemNames[i];
87 }
88 std::cout << std::endl << std::endl;
89
90 // Run benchmarks on all problems
91 std::cout << "Running benchmarks..." << std::endl;
92 auto results = benchmarker.benchmarkAll(benchmarkTrials, timeoutSeconds, true);
93
94 // Print statistics for each problem
95 if (benchmarkTrials > 0)
96 {
97 std::cout << "Benchmark Results Saved, use python script to transfer to .db" << std::endl;
98 }
99 else
100 {
101 for (const auto &[problemName, problemResults] : results)
102 {
103 MotionBenchmakerDemo::printStatistics(problemName, problemResults);
104 }
105 }
106 }
107 catch (const std::exception &e)
108 {
109 std::cerr << "Error: " << e.what() << std::endl;
110 return 1;
111 }
112
113 return 0;
114}
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.